diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 82dc180dda32..1d3465cc7e36 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -81,15 +81,19 @@ void Ekf::reset() resetGpsDriftCheckFilters(); _output_predictor.reset(); + + _filter_initialised = false; } bool Ekf::update() { + bool updated = false; + if (!_filter_initialised) { - _filter_initialised = initialiseFilter(); + if (initialiseFilter()) { + _filter_initialised = true; - if (!_filter_initialised) { - return false; + _output_predictor.resetAlignment(); } } @@ -101,23 +105,25 @@ bool Ekf::update() // TODO: explicitly pop at desired time horizon const imuSample imu_sample_delayed = _imu_buffer.get_oldest(); - // perform state and covariance prediction for the main filter - predictCovariance(imu_sample_delayed); - predictState(imu_sample_delayed); + if (_filter_initialised) { + // perform state and covariance prediction for the main filter + predictCovariance(imu_sample_delayed); + predictState(imu_sample_delayed); - // control fusion of observation data - controlFusionModes(imu_sample_delayed); + // control fusion of observation data + controlFusionModes(imu_sample_delayed); - // run a separate filter for terrain estimation - runTerrainEstimator(imu_sample_delayed); + // run a separate filter for terrain estimation + runTerrainEstimator(imu_sample_delayed); - _output_predictor.correctOutputStates(imu_sample_delayed.time_us, getGyroBias(), getAccelBias(), - _state.quat_nominal, _state.vel, _state.pos); + updated = true; + } - return true; + _output_predictor.correctOutputStates(imu_sample_delayed.time_us, getGyroBias(), getAccelBias(), + _state.quat_nominal, _state.vel, _state.pos); } - return false; + return updated; } bool Ekf::initialiseFilter() @@ -203,9 +209,6 @@ bool Ekf::initialiseFilter() _time_last_hor_pos_fuse = _time_delayed_us; _time_last_hor_vel_fuse = _time_delayed_us; - // reset the output predictor state history to match the EKF initial values - _output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _state.pos); - return true; } diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 8697e1e688fa..c19ce63c899d 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -71,7 +71,7 @@ void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f P.uncorrelateCovarianceSetVariance<1>(5, math::max(sq(0.01f), new_horz_vel_var(1))); } - _output_predictor.resetHorizontalVelocityTo(delta_horz_vel); + _output_predictor.resetHorizontalVelocityTo(new_horz_vel); // record the state change if (_state_reset_status.reset_count.velNE == _state_reset_count_prev.velNE) { @@ -168,7 +168,7 @@ bool Ekf::isHeightResetRequired() const void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_var) { - const float old_vert_pos = _state.pos(2); + const float delta_z = new_vert_pos - _state.pos(2); _state.pos(2) = new_vert_pos; if (PX4_ISFINITE(new_vert_pos_var)) { @@ -176,11 +176,9 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_v P.uncorrelateCovarianceSetVariance<1>(9, math::max(sq(0.01f), new_vert_pos_var)); } - const float delta_z = new_vert_pos - old_vert_pos; - // apply the change in height / height rate to our newest height / height rate estimate // which have already been taken out from the output buffer - _output_predictor.resetVerticalPositionTo(new_vert_pos, delta_z); + _output_predictor.resetVerticalPositionTo(new_vert_pos); // record the state change if (_state_reset_status.reset_count.posD == _state_reset_count_prev.posD) { @@ -1292,8 +1290,11 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) increaseQuatYawErrVariance(yaw_variance); } + // apply change to velocity state + _state.vel = q_error.rotateVector(_state.vel); + // add the reset amount to the output observer buffered data - _output_predictor.resetQuaternion(q_error); + _output_predictor.resetQuaternion(quat_after_reset); // record the state change if (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) { diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index ea5f66e38e31..7b741789cd58 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -448,7 +448,7 @@ void EstimatorInterface::setSystemFlagData(const systemFlagUpdate &system_flags) _system_flag_buffer->push(system_flags_new); } else { - ECL_WARN("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _system_flag_buffer->get_newest().time_us, _min_obs_interval_us); + //ECL_WARN("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _system_flag_buffer->get_newest().time_us, _min_obs_interval_us); } } diff --git a/src/modules/ekf2/EKF/output_predictor.cpp b/src/modules/ekf2/EKF/output_predictor.cpp index bdb8077ea05a..86941a1f16dd 100644 --- a/src/modules/ekf2/EKF/output_predictor.cpp +++ b/src/modules/ekf2/EKF/output_predictor.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4. All rights reserved. + * Copyright (c) 2022-2023 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -48,39 +48,13 @@ void OutputPredictor::print_status() printf("output buffer: %d/%d (%d Bytes)\n", _output_buffer.entries(), _output_buffer.get_length(), _output_buffer.get_total_size()); - - printf("output vert buffer: %d/%d (%d Bytes)\n", _output_vert_buffer.entries(), _output_vert_buffer.get_length(), - _output_vert_buffer.get_total_size()); -} - -void OutputPredictor::alignOutputFilter(const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state) -{ - const outputSample &output_delayed = _output_buffer.get_oldest(); - - // calculate the quaternion rotation delta from the EKF to output observer states at the EKF fusion time horizon - Quatf q_delta{quat_state * output_delayed.quat_nominal.inversed()}; - q_delta.normalize(); - - // calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon - const Vector3f vel_delta = vel_state - output_delayed.vel; - const Vector3f pos_delta = pos_state - output_delayed.pos; - - // loop through the output filter state history and add the deltas - for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { - _output_buffer[i].quat_nominal = q_delta * _output_buffer[i].quat_nominal; - _output_buffer[i].quat_nominal.normalize(); - _output_buffer[i].vel += vel_delta; - _output_buffer[i].pos += pos_delta; - } - - _output_new = _output_buffer.get_newest(); } void OutputPredictor::reset() { - // TODO: who resets the output buffer content? - _output_new = {}; - _output_vert_new = {}; + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index] = {}; + } _accel_bias.setZero(); _gyro_bias.setZero(); @@ -88,86 +62,171 @@ void OutputPredictor::reset() _time_last_update_states_us = 0; _time_last_correct_states_us = 0; + _output_new = {}; _R_to_earth_now.setIdentity(); - _vel_imu_rel_body_ned.setZero(); - _vel_deriv.setZero(); - - _delta_angle_corr.setZero(); + _vel_imu_rel_body_ned.zero(); + _vel_deriv.zero(); - _vel_err_integ.setZero(); - _pos_err_integ.setZero(); + _delta_angle_corr.zero(); + _vel_err_integ.zero(); + _pos_err_integ.zero(); - _output_tracking_error.setZero(); + _output_tracking_error.zero(); - for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { - _output_buffer[index] = {}; - } - - for (uint8_t index = 0; index < _output_vert_buffer.get_length(); index++) { - _output_vert_buffer[index] = {}; - } + _output_filter_aligned = false; } -void OutputPredictor::resetQuaternion(const Quatf &quat_change) +void OutputPredictor::resetQuaternion(const Quatf &new_quat) { + const outputSample &output_delayed = _output_buffer.get_oldest(); + const Quatf quat_change{(new_quat * output_delayed.quat_nominal.inversed()).normalized()}; + // add the reset amount to the output observer buffered data for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { - _output_buffer[i].quat_nominal = quat_change * _output_buffer[i].quat_nominal; + _output_buffer[i].quat_nominal = (quat_change * _output_buffer[i].quat_nominal).normalized(); + + // apply change to velocity + _output_buffer[i].vel = quat_change.rotateVector(_output_buffer[i].vel); + _output_buffer[i].vel_alternative = quat_change.rotateVector(_output_buffer[i].vel_alternative); } // apply the change in attitude quaternion to our newest quaternion estimate - // which was already taken out from the output buffer - _output_new.quat_nominal = quat_change * _output_new.quat_nominal; + _output_new.quat_nominal = (quat_change * _output_new.quat_nominal).normalized(); + _R_to_earth_now = Dcmf(_output_new.quat_nominal); + + // apply change to velocity + _output_new.vel = quat_change.rotateVector(_output_new.vel); + _output_new.vel_alternative = quat_change.rotateVector(_output_new.vel_alternative); + + propagateVelocityUpdateToPosition(); } -void OutputPredictor::resetHorizontalVelocityTo(const Vector2f &delta_horz_vel) +void OutputPredictor::resetHorizontalVelocityTo(const Vector2f &new_horz_vel) { - for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { - _output_buffer[index].vel.xy() += delta_horz_vel; + const outputSample &output_delayed = _output_buffer.get_oldest(); + + // horizontal velocity + { + const Vector2f delta_vxy = new_horz_vel - Vector2f(output_delayed.vel.xy()); + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index].vel.xy() += delta_vxy; + } + + _output_new.vel.xy() += delta_vxy; } - _output_new.vel.xy() += delta_horz_vel; + // horizontal velocity (alternative) + { + const Vector2f delta_vxy = new_horz_vel - Vector2f(output_delayed.vel_alternative.xy()); + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index].vel_alternative.xy() += delta_vxy; + } + + _output_new.vel_alternative.xy() += delta_vxy; + } + + // propagate position forward using the reset velocity + propagateVelocityUpdateToPosition(); } -void OutputPredictor::resetVerticalVelocityTo(float delta_vert_vel) +void OutputPredictor::resetVerticalVelocityTo(const float new_vert_vel) { - for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { - _output_buffer[index].vel(2) += delta_vert_vel; - _output_vert_buffer[index].vert_vel += delta_vert_vel; + const outputSample &output_delayed = _output_buffer.get_oldest(); + + // vertical velocity + { + const float delta_z = new_vert_vel - output_delayed.vel(2); + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index].vel(2) += delta_z; + } + + _output_new.vel(2) += delta_z; + } + + // vertical velocity (alternative) + { + const float delta_z = new_vert_vel - output_delayed.vel_alternative(2); + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index].vel_alternative(2) += delta_z; + } + + _output_new.vel_alternative(2) += delta_z; } - _output_new.vel(2) += delta_vert_vel; - _output_vert_new.vert_vel += delta_vert_vel; + // propagate vertical position forward using the reset velocity + propagateVelocityUpdateToPosition(); } -void OutputPredictor::resetHorizontalPositionTo(const Vector2f &delta_horz_pos) +void OutputPredictor::resetHorizontalPositionTo(const Vector2f &new_horz_pos) { - for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { - _output_buffer[index].pos.xy() += delta_horz_pos; + const outputSample &output_delayed = _output_buffer.get_oldest(); + + // horizontal velocity + { + const Vector2f delta_xy = new_horz_pos - output_delayed.pos.xy(); + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index].pos.xy() += delta_xy; + } + + _output_new.pos.xy() += delta_xy; } - _output_new.pos.xy() += delta_horz_pos; + // horizontal velocity (alternative) + { + const Vector2f delta_xy = new_horz_pos - output_delayed.vel_alternative_integ.xy(); + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + _output_buffer[index].vel_alternative_integ.xy() += delta_xy; + } + + _output_new.vel_alternative_integ.xy() += delta_xy; + } } -void OutputPredictor::resetVerticalPositionTo(const float new_vert_pos, const float vert_pos_change) +void OutputPredictor::resetVerticalPositionTo(const float new_vert_pos) { - // apply the change in height / height rate to our newest height / height rate estimate - // which have already been taken out from the output buffer - _output_new.pos(2) += vert_pos_change; + const outputSample &output_delayed = _output_buffer.get_oldest(); - // add the reset amount to the output observer buffered data - for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { - _output_buffer[i].pos(2) += vert_pos_change; - _output_vert_buffer[i].vert_vel_integ += vert_pos_change; + // vertical position + { + const float delta_z = new_vert_pos - output_delayed.pos(2); + + // add the reset amount to the output observer buffered data + for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { + _output_buffer[i].pos(2) += delta_z; + } + + // apply the change in height / height rate to our newest height / height rate estimate + // which have already been taken out from the output buffer + _output_new.pos(2) += delta_z; } - // add the reset amount to the output observer vertical position state - _output_vert_new.vert_vel_integ = new_vert_pos; + // vertical position (alternative) + { + const float delta_z = new_vert_pos - output_delayed.vel_alternative_integ(2); + + // add the reset amount to the output observer buffered data + for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { + _output_buffer[i].vel_alternative_integ(2) += delta_z; + } + + // add the reset amount to the output observer vertical position state + _output_new.vel_alternative_integ(2) += delta_z; + } } -void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector3f &delta_angle, +bool OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector3f &delta_angle, const float delta_angle_dt, const Vector3f &delta_velocity, const float delta_velocity_dt) { + if (time_us <= _time_last_update_states_us) { + return false; + } + // Use full rate IMU data at the current time horizon if (_time_last_update_states_us != 0) { const float dt = math::constrain((time_us - _time_last_update_states_us) * 1e-6f, 0.0001f, 0.03f); @@ -185,18 +244,11 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector const Vector3f delta_velocity_corrected(delta_velocity - delta_vel_bias_scaled); _output_new.time_us = time_us; - _output_vert_new.time_us = time_us; - - const Quatf dq(AxisAnglef{delta_angle_corrected}); // rotate the previous INS quaternion by the delta quaternions - _output_new.quat_nominal = _output_new.quat_nominal * dq; - - // the quaternions must always be normalised after modification - _output_new.quat_nominal.normalize(); - - // calculate the rotation matrix from body to earth frame - _R_to_earth_now = Dcmf(_output_new.quat_nominal); + const Quatf dq(AxisAnglef{delta_angle_corrected}); + _output_new.quat_nominal = (_output_new.quat_nominal * dq).normalized(); + _R_to_earth_now = Dcmf(_output_new.quat_nominal); // calculate the rotation matrix from body to earth frame // rotate the delta velocity to earth frame Vector3f delta_vel_earth{_R_to_earth_now * delta_velocity_corrected}; @@ -215,16 +267,16 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector // increment the INS velocity states by the measurement plus corrections // do the same for vertical state used by alternative correction algorithm _output_new.vel += delta_vel_earth; - _output_vert_new.vert_vel += delta_vel_earth(2); + _output_new.vel_alternative += delta_vel_earth; // use trapezoidal integration to calculate the INS position states // do the same for vertical state used by alternative correction algorithm const Vector3f delta_pos_NED = (_output_new.vel + vel_last) * (delta_velocity_dt * 0.5f); _output_new.pos += delta_pos_NED; - _output_vert_new.vert_vel_integ += delta_pos_NED(2); + _output_new.vel_alternative_integ += delta_pos_NED; // accumulate the time for each update - _output_vert_new.dt += delta_velocity_dt; + _output_new.dt += delta_velocity_dt; // correct velocity for IMU offset if (delta_angle_dt > 0.001f) { @@ -237,12 +289,28 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector // rotate the relative velocity into earth frame _vel_imu_rel_body_ned = _R_to_earth_now * vel_imu_rel_body; } + + return true; } void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias, const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state) { + const uint64_t time_latest_us = _time_last_update_states_us; + + if (time_latest_us <= time_delayed_us || time_delayed_us <= _time_last_correct_states_us) { + return; + } + + // store the INS states in a ring buffer with the same length and time coordinates as the IMU data buffer + _output_buffer.push(_output_new); + _output_new.dt = 0.0f; // reset time delta to zero for the next accumulation of full rate IMU data + + // store IMU bias for calculateOutputStates + _gyro_bias = gyro_bias; + _accel_bias = accel_bias; + // calculate an average filter update time if (_time_last_correct_states_us != 0) { const float dt = math::constrain((time_delayed_us - _time_last_correct_states_us) * 1e-6f, 0.0001f, 0.03f); @@ -251,124 +319,207 @@ void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, _time_last_correct_states_us = time_delayed_us; - // store IMU bias for calculateOutputStates - _gyro_bias = gyro_bias; - _accel_bias = accel_bias; - - // store the INS states in a ring buffer with the same length and time coordinates as the IMU data buffer - _output_buffer.push(_output_new); - _output_vert_buffer.push(_output_vert_new); // get the oldest INS state data from the ring buffer // this data will be at the EKF fusion time horizon - // TODO: there is no guarantee that data is at delayed fusion horizon - // Shouldnt we use pop_first_older_than? - const outputSample &output_delayed = _output_buffer.get_oldest(); - const outputVert &output_vert_delayed = _output_vert_buffer.get_oldest(); + outputSample output_delayed; - // calculate the quaternion delta between the INS and EKF quaternions at the EKF fusion time horizon - const Quatf q_error((quat_state.inversed() * output_delayed.quat_nominal).normalized()); + while (_output_buffer.pop_first_older_than(time_delayed_us, &output_delayed)) { - // convert the quaternion delta to a delta angle - const float scalar = (q_error(0) >= 0.0f) ? -2.f : 2.f; + if (output_delayed.time_us != time_delayed_us) { + continue; + } - const Vector3f delta_ang_error{scalar * q_error(1), scalar * q_error(2), scalar * q_error(3)}; + if (!_output_filter_aligned) { - // calculate a gain that provides tight tracking of the estimator attitude states and - // adjust for changes in time delay to maintain consistent damping ratio of ~0.7 - const uint64_t time_latest_us = _time_last_update_states_us; - const float time_delay = fmaxf((time_latest_us - time_delayed_us) * 1e-6f, _dt_update_states_avg); - const float att_gain = 0.5f * _dt_update_states_avg / time_delay; + // calculate the quaternion rotation delta from the EKF to output observer states at the EKF fusion time horizon + const Quatf q_delta((quat_state * output_delayed.quat_nominal.inversed()).normalized()); - // calculate a corrrection to the delta angle - // that will cause the INS to track the EKF quaternions - _delta_angle_corr = delta_ang_error * att_gain; - _output_tracking_error(0) = delta_ang_error.norm(); + // add the reset amount to the output observer buffered data + for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { - /* - * Loop through the output filter state history and apply the corrections to the velocity and position states. - * This method is too expensive to use for the attitude states due to the quaternion operations required - * but because it eliminates the time delay in the 'correction loop' it allows higher tracking gains - * to be used and reduces tracking error relative to EKF states. - */ + _output_buffer[i].quat_nominal = (q_delta * _output_buffer[i].quat_nominal).normalized(); - // Complementary filter gains - const float vel_gain = _dt_correct_states_avg / math::constrain(_vel_tau, _dt_correct_states_avg, 10.f); - const float pos_gain = _dt_correct_states_avg / math::constrain(_pos_tau, _dt_correct_states_avg, 10.f); + // apply change to velocity + _output_buffer[i].vel = q_delta.rotateVector(_output_buffer[i].vel); + _output_buffer[i].vel_alternative = q_delta.rotateVector(_output_buffer[i].vel_alternative); + } - // calculate down velocity and position tracking errors - const float vert_vel_err = (vel_state(2) - output_vert_delayed.vert_vel); - const float vert_vel_integ_err = (pos_state(2) - output_vert_delayed.vert_vel_integ); + // apply the change in attitude quaternion to our newest quaternion estimate + _output_new.quat_nominal = (q_delta * _output_new.quat_nominal).normalized(); - // calculate a velocity correction that will be applied to the output state history - // using a PD feedback tuned to a 5% overshoot - const float vert_vel_correction = vert_vel_integ_err * pos_gain + vert_vel_err * vel_gain * 1.1f; - applyCorrectionToVerticalOutputBuffer(vert_vel_correction); + // apply change to velocity + _output_new.vel = q_delta.rotateVector(_output_new.vel); + _output_new.vel_alternative = q_delta.rotateVector(_output_new.vel_alternative); - // calculate velocity and position tracking errors - const Vector3f vel_err(vel_state - output_delayed.vel); - const Vector3f pos_err(pos_state - output_delayed.pos); + propagateVelocityUpdateToPosition(); - _output_tracking_error(1) = vel_err.norm(); - _output_tracking_error(2) = pos_err.norm(); - // calculate a velocity correction that will be applied to the output state history - _vel_err_integ += vel_err; - const Vector3f vel_correction = vel_err * vel_gain + _vel_err_integ * sq(vel_gain) * 0.1f; + // calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon + output_delayed.vel = q_delta.rotateVectorInverse(output_delayed.vel); + const Vector3f vel_err = vel_state - output_delayed.vel; - // calculate a position correction that will be applied to the output state history - _pos_err_integ += pos_err; - const Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f; + output_delayed.vel_alternative = q_delta.rotateVectorInverse(output_delayed.vel_alternative); + const Vector3f vel_alternative_err = vel_state - output_delayed.vel_alternative; - applyCorrectionToOutputBuffer(vel_correction, pos_correction); -} + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + // a constant velocity correction is applied + _output_buffer[index].vel += vel_err; + _output_buffer[index].vel_alternative += vel_alternative_err; + } -void OutputPredictor::applyCorrectionToVerticalOutputBuffer(float vert_vel_correction) -{ - // loop through the vertical output filter state history starting at the oldest and apply the corrections to the - // vert_vel states and propagate vert_vel_integ forward using the corrected vert_vel - uint8_t index = _output_vert_buffer.get_oldest_index(); + // manually correct next oldest state + // position is propagated forward using the corrected velocity and a trapezoidal integrator + uint8_t index = _output_buffer.get_oldest_index(); + outputSample &next_oldest_state = _output_buffer[index]; - const uint8_t size = _output_vert_buffer.get_length(); + if ((next_oldest_state.time_us > output_delayed.time_us) && (next_oldest_state.dt > 0.f)) { - for (uint8_t counter = 0; counter < (size - 1); counter++) { - const uint8_t index_next = (index + 1) % size; - outputVert ¤t_state = _output_vert_buffer[index]; - outputVert &next_state = _output_vert_buffer[index_next]; + next_oldest_state.pos = pos_state + (vel_state + next_oldest_state.vel) * 0.5f * next_oldest_state.dt; + next_oldest_state.vel_alternative_integ = pos_state + (vel_state + next_oldest_state.vel_alternative) * 0.5f * + next_oldest_state.dt; - // correct the velocity - if (counter == 0) { - current_state.vert_vel += vert_vel_correction; - } + propagateVelocityUpdateToPosition(); + } - next_state.vert_vel += vert_vel_correction; + _output_new = _output_buffer.get_newest(); + _output_new.dt = 0.0f; - // position is propagated forward using the corrected velocity and a trapezoidal integrator - next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f * next_state.dt; + // reset tracking error, integral, etc + _output_tracking_error.zero(); + _delta_angle_corr.zero(); + _vel_err_integ.zero(); + _pos_err_integ.zero(); - // advance the index - index = (index + 1) % size; + _output_filter_aligned = true; + + } else { + + /* + * Loop through the output filter state history and apply the corrections to the velocity and position states. + * This method is too expensive to use for the attitude states due to the quaternion operations required + * but because it eliminates the time delay in the 'correction loop' it allows higher tracking gains + * to be used and reduces tracking error relative to EKF states. + */ + + // calculate the quaternion delta between the INS and EKF quaternions at the EKF fusion time horizon + const Quatf q_error((quat_state.inversed() * output_delayed.quat_nominal).normalized()); + + // convert the quaternion delta to a delta angle + const float scalar = (q_error(0) >= 0.0f) ? -2.f : 2.f; + + const Vector3f delta_ang_error{scalar * q_error(1), scalar * q_error(2), scalar * q_error(3)}; + + // calculate a gain that provides tight tracking of the estimator attitude states and + // adjust for changes in time delay to maintain consistent damping ratio of ~0.7 + + const float time_delay = fmaxf((time_latest_us - time_delayed_us) * 1e-6f, _dt_update_states_avg); + const float att_gain = 0.5f * _dt_update_states_avg / time_delay; + + // calculate a corrrection to the delta angle + // that will cause the INS to track the EKF quaternions + _delta_angle_corr = delta_ang_error * att_gain; + _output_tracking_error(0) = delta_ang_error.norm(); + + + /* + * Calculate corrections to be applied to vel and pos output state history. + * The vel and pos state history are corrected individually so they track the EKF states at + * the fusion time horizon. This option provides the most accurate tracking of EKF states. + */ + + // calculate velocity tracking errors + const Vector3f vel_err = vel_state - output_delayed.vel; + _output_tracking_error(1) = vel_err.norm(); + // calculate a velocity correction that will be applied to the output state history + const float vel_gain = _dt_correct_states_avg / math::constrain(_vel_tau, _dt_correct_states_avg, + 10.f); // Complementary filter gains + _vel_err_integ += vel_err; + const Vector3f vel_correction = vel_err * vel_gain + _vel_err_integ * sq(vel_gain) * 0.1f; + + // calculate position tracking errors + const Vector3f pos_err = pos_state - output_delayed.pos; + _output_tracking_error(2) = pos_err.norm(); + // calculate a position correction that will be applied to the output state history + const float pos_gain = _dt_correct_states_avg / math::constrain(_pos_tau, _dt_correct_states_avg, + 10.f); // Complementary filter gains + _pos_err_integ += pos_err; + const Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f; + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + // a constant velocity correction is applied + _output_buffer[index].vel += vel_correction; + _output_buffer[index].pos += pos_correction; + } + + + /* + * Calculate a correction to be applied to vel_alternative that casues vel_alternative_integ to track the EKF + * position state at the fusion time horizon using an alternative algorithm to what + * is used for the vel and pos state tracking. The algorithm applies a correction to the vel_alternative + * state history and propagates vel_alternative_integ forward in time using the corrected vel_alternative history. + * This provides an alternative velocity output that is closer to the first derivative + * of the position but does degrade tracking relative to the EKF state. + */ + + // vel alternative: calculate velocity and position tracking errors + const Vector3f vel_alternative_err = (vel_state - output_delayed.vel_alternative); + const Vector3f vel_alternative_integ_err = (pos_state - output_delayed.vel_alternative_integ); + + // calculate a velocity correction that will be applied to the output state history + // using a PD feedback tuned to a 5% overshoot + const Vector3f vel_alternative_correction = vel_alternative_integ_err * pos_gain + vel_alternative_err * vel_gain * + 1.1f; + + for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { + // a constant velocity correction is applied + _output_buffer[index].vel_alternative += vel_alternative_correction; + _output_buffer[index].vel_alternative_integ += vel_alternative_integ_err; + } + + // recompute position by integrating velocity + propagateVelocityUpdateToPosition(); + } } - // update output state to corrected values - _output_vert_new = _output_vert_buffer.get_newest(); + _output_new = _output_buffer.get_newest(); + _output_new.dt = 0.f; - // reset time delta to zero for the next accumulation of full rate IMU data - _output_vert_new.dt = 0.0f; + _R_to_earth_now = Dcmf(_output_new.quat_nominal); } -void OutputPredictor::applyCorrectionToOutputBuffer(const Vector3f &vel_correction, const Vector3f &pos_correction) +void OutputPredictor::propagateVelocityUpdateToPosition() { - // loop through the output filter state history and apply the corrections to the velocity and position states - for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { - // a constant velocity correction is applied - _output_buffer[index].vel += vel_correction; + // propagate position forward using the reset velocity + uint8_t index = _output_buffer.get_oldest_index(); + const uint8_t size = _output_buffer.get_length(); + + for (uint8_t counter = 0; counter < (size - 1); counter++) { + + const outputSample ¤t_state = _output_buffer[index]; + + // next state + const uint8_t index_next = (index + 1) % size; + outputSample &next_state = _output_buffer[index_next]; - // a constant position correction is applied - _output_buffer[index].pos += pos_correction; + if ((next_state.time_us > current_state.time_us) && (next_state.dt > 0.f)) { + // position is propagated forward using the corrected velocity and a trapezoidal integrator + next_state.pos = current_state.pos + (current_state.vel + next_state.vel) * 0.5f * next_state.dt; + next_state.vel_alternative_integ = current_state.vel_alternative_integ + (current_state.vel_alternative + + next_state.vel_alternative) * 0.5f * next_state.dt; + } + + // advance the index + index = (index + 1) % size; } - // update output state to corrected values - _output_new = _output_buffer.get_newest(); + if (_output_new.time_us > _output_buffer.get_newest().time_us) { + // position is propagated forward using the corrected velocity and a trapezoidal integrator + _output_new.pos = _output_buffer.get_newest().pos + + (_output_buffer.get_newest().vel + _output_new.vel) * 0.5f * _output_new.dt; + + _output_new.vel_alternative_integ = _output_buffer.get_newest().vel_alternative_integ + + (_output_buffer.get_newest().vel_alternative + _output_new.vel_alternative) * 0.5f * _output_new.dt; + } } diff --git a/src/modules/ekf2/EKF/output_predictor.h b/src/modules/ekf2/EKF/output_predictor.h index 5eb3b44e2fab..eeae96d8b243 100644 --- a/src/modules/ekf2/EKF/output_predictor.h +++ b/src/modules/ekf2/EKF/output_predictor.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2022 PX4. All rights reserved. + * Copyright (c) 2022-2023 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -51,9 +51,6 @@ class OutputPredictor ~OutputPredictor() = default; - // modify output filter to match the the EKF state at the fusion time horizon - void alignOutputFilter(const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, - const matrix::Vector3f &pos_state); /* * Implement a strapdown INS algorithm using the latest IMU data at the current time horizon. * Buffer the INS states and calculate the difference with the EKF states at the delayed fusion time horizon. @@ -64,26 +61,26 @@ class OutputPredictor * “Recursive Attitude Estimation in the Presence of Multi-rate and Multi-delay Vector Measurements” * A Khosravian, J Trumpf, R Mahony, T Hamel, Australian National University */ - void calculateOutputStates(const uint64_t time_us, const matrix::Vector3f &delta_angle, const float delta_angle_dt, + bool calculateOutputStates(const uint64_t time_us, const matrix::Vector3f &delta_angle, const float delta_angle_dt, const matrix::Vector3f &delta_velocity, const float delta_velocity_dt); void correctOutputStates(const uint64_t time_delayed_us, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias, const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state); - void resetQuaternion(const matrix::Quatf &quat_change); + void resetQuaternion(const matrix::Quatf &new_quat); - void resetHorizontalVelocityTo(const matrix::Vector2f &delta_horz_vel); - void resetVerticalVelocityTo(float delta_vert_vel); + void resetHorizontalVelocityTo(const matrix::Vector2f &new_horz_vel); + void resetVerticalVelocityTo(const float new_vert_vel); - void resetHorizontalPositionTo(const matrix::Vector2f &delta_horz_pos); - void resetVerticalPositionTo(const float new_vert_pos, const float vert_pos_change); + void resetHorizontalPositionTo(const matrix::Vector2f &new_horz_pos); + void resetVerticalPositionTo(const float new_vert_pos); void print_status(); bool allocate(uint8_t size) { - if (_output_buffer.allocate(size) && _output_vert_buffer.allocate(size)) { + if (_output_buffer.allocate(size)) { reset(); return true; } @@ -93,6 +90,8 @@ class OutputPredictor void reset(); + void resetAlignment() { _output_filter_aligned = false; } + const matrix::Quatf &getQuaternion() const { return _output_new.quat_nominal; } // get the velocity of the body frame origin in local NED earth frame @@ -102,7 +101,7 @@ class OutputPredictor const matrix::Vector3f &getVelocityDerivative() const { return _vel_deriv; } // get the derivative of the vertical position of the body frame origin in local NED earth frame - float getVerticalPositionDerivative() const { return _output_vert_new.vert_vel - _vel_imu_rel_body_ned(2); } + float getVerticalPositionDerivative() const { return _output_new.vel_alternative(2) - _vel_imu_rel_body_ned(2); } // get the position of the body frame origin in local earth frame matrix::Vector3f getPosition() const @@ -117,48 +116,32 @@ class OutputPredictor // error magnitudes (rad), (m/sec), (m) const matrix::Vector3f &getOutputTrackingError() const { return _output_tracking_error; } + bool aligned() const { return _output_filter_aligned; } + void set_imu_offset(const matrix::Vector3f &offset) { _imu_pos_body = offset; } void set_pos_correction_tc(const float tau) { _pos_tau = tau; } void set_vel_correction_tc(const float tau) { _vel_tau = tau; } private: - /* - * Calculate a correction to be applied to vert_vel that casues vert_vel_integ to track the EKF - * down position state at the fusion time horizon using an alternative algorithm to what - * is used for the vel and pos state tracking. The algorithm applies a correction to the vert_vel - * state history and propagates vert_vel_integ forward in time using the corrected vert_vel history. - * This provides an alternative vertical velocity output that is closer to the first derivative - * of the position but does degrade tracking relative to the EKF state. - */ - void applyCorrectionToVerticalOutputBuffer(float vert_vel_correction); - - /* - * Calculate corrections to be applied to vel and pos output state history. - * The vel and pos state history are corrected individually so they track the EKF states at - * the fusion time horizon. This option provides the most accurate tracking of EKF states. - */ - void applyCorrectionToOutputBuffer(const matrix::Vector3f &vel_correction, const matrix::Vector3f &pos_correction); + void propagateVelocityUpdateToPosition(); // return the square of two floating point numbers - used in auto coded sections static constexpr float sq(float var) { return var * var; } struct outputSample { - uint64_t time_us{0}; ///< timestamp of the measurement (uSec) - matrix::Quatf quat_nominal{1.f, 0.f, 0.f, 0.f}; ///< nominal quaternion describing vehicle attitude - matrix::Vector3f vel{0.f, 0.f, 0.f}; ///< NED velocity estimate in earth frame (m/sec) - matrix::Vector3f pos{0.f, 0.f, 0.f}; ///< NED position estimate in earth frame (m/sec) - }; + uint64_t time_us{0}; ///< timestamp of the measurement (uSec) + matrix::Quatf quat_nominal{1.f, 0.f, 0.f, 0.f}; ///< nominal quaternion describing vehicle attitude + matrix::Vector3f vel{0.f, 0.f, 0.f}; ///< NED velocity estimate in earth frame (m/sec) + matrix::Vector3f pos{0.f, 0.f, 0.f}; ///< NED position estimate in earth frame (m/sec) - struct outputVert { - uint64_t time_us{0}; ///< timestamp of the measurement (uSec) - float vert_vel{0.f}; ///< Vertical velocity calculated using alternative algorithm (m/sec) - float vert_vel_integ{0.f}; ///< Integral of vertical velocity (m) - float dt{0.f}; ///< delta time (sec) + matrix::Vector3f vel_alternative{0.f, 0.f, 0.f}; ///< NED velocity calculated using alternative algorithm (m/sec) + matrix::Vector3f vel_alternative_integ{0.f, 0.f, 0.f}; ///< NED integral of velocity (m) + + float dt{0.f}; ///< delta time (sec) }; RingBuffer _output_buffer{12}; - RingBuffer _output_vert_buffer{12}; matrix::Vector3f _accel_bias{}; matrix::Vector3f _gyro_bias{}; @@ -171,7 +154,6 @@ class OutputPredictor // Output Predictor outputSample _output_new{}; // filter output on the non-delayed time horizon - outputVert _output_vert_new{}; // vertical filter output on the non-delayed time horizon matrix::Matrix3f _R_to_earth_now{}; // rotation matrix from body to earth frame at current time matrix::Vector3f _vel_imu_rel_body_ned{}; // velocity of IMU relative to body origin in NED earth frame matrix::Vector3f _vel_deriv{}; // velocity derivative at the IMU in NED earth frame (m/s/s) @@ -183,6 +165,8 @@ class OutputPredictor matrix::Vector3f _output_tracking_error{}; ///< contains the magnitude of the angle, velocity and position track errors (rad, m/s, m) + bool _output_filter_aligned{false}; + matrix::Vector3f _imu_pos_body{}; ///< xyz position of IMU in body frame (m) // output complementary filter tuning diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 7e90b56d932d..0b344bf27b69 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -608,33 +608,38 @@ void EKF2::Run() if (_ekf.update()) { perf_set_elapsed(_ecl_ekf_update_full_perf, hrt_elapsed_time(&ekf_update_start)); - PublishLocalPosition(now); - PublishOdometry(now, imu_sample_new); - PublishGlobalPosition(now); + if (_ekf.attitude_valid() && _ekf.output_predictor().aligned()) { + // publish output predictor output + PublishLocalPosition(now); + PublishOdometry(now, imu_sample_new); + PublishGlobalPosition(now); + } + + // publish other state output used by the system not dependent on output predictor + PublishSensorBias(now); PublishWindEstimate(now); // publish status/logging messages + PublishAidSourceStatus(now); PublishBaroBias(now); - PublishGnssHgtBias(now); - PublishRngHgtBias(now); - PublishEvPosBias(now); PublishEventFlags(now); + PublishEvPosBias(now); + PublishGnssHgtBias(now); PublishGpsStatus(now); PublishInnovations(now); PublishInnovationTestRatios(now); PublishInnovationVariances(now); PublishOpticalFlowVel(now); + PublishRngHgtBias(now); PublishStates(now); PublishStatus(now); PublishStatusFlags(now); PublishYawEstimatorStatus(now); + // online accel/gyro/mag calibration UpdateAccelCalibration(now); UpdateGyroCalibration(now); UpdateMagCalibration(now); - PublishSensorBias(now); - - PublishAidSourceStatus(now); } else { // ekf no update @@ -793,7 +798,7 @@ void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp) void EKF2::PublishAttitude(const hrt_abstime ×tamp) { - if (_ekf.attitude_valid()) { + if (_ekf.attitude_valid() && _ekf.output_predictor().aligned()) { // generate vehicle attitude quaternion data vehicle_attitude_s att; att.timestamp_sample = timestamp; @@ -803,7 +808,7 @@ void EKF2::PublishAttitude(const hrt_abstime ×tamp) att.timestamp = _replay_mode ? timestamp : hrt_absolute_time(); _attitude_pub.publish(att); - } else if (_replay_mode) { + } else if (_replay_mode) { // in replay mode we have to tell the replay module not to wait for an update // we do this by publishing an attitude with zero timestamp vehicle_attitude_s att{}; diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index 3679bb53b0a9..a8f378fa7381 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -63,329 +63,329 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6090000,1,-0.0095,-0.011,-0.022,0.0053,0.0052,-0.011,0.0021,0.00027,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,-7.6e-12,7.7e-12,-3.8e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-07,0.00038,0.00038,0.00016,0.23,0.23,7,0.1,0.1,0.33,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 6190000,1,-0.0095,-0.011,-0.022,0.0056,0.0072,-0.0049,0.0027,0.00092,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,-7.6e-12,7.7e-12,-4e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00041,0.00041,0.00016,0.27,0.27,4.9,0.13,0.13,0.32,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 6290000,1,-0.0095,-0.011,-0.022,0.0071,0.0075,-0.012,0.0033,0.0016,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,-7.6e-12,7.7e-12,-4.1e-06,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00043,0.00043,0.00016,0.31,0.31,3.2,0.17,0.17,0.3,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,-7.6e-12,7.7e-12,-3.5e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,-7.6e-12,7.7e-12,-4e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6590000,0.71,0.0015,-0.014,0.71,0.0036,0.0085,-0.099,0.0034,0.0033,-3.7e+02,-1.6e-05,-5.6e-05,3.6e-07,-7.6e-12,7.7e-12,-2.2e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00039,0.00034,0.00034,0.00043,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6690000,0.7,0.0015,-0.014,0.71,0.0037,0.0095,-0.076,0.0037,0.0042,-3.7e+02,-1.6e-05,-5.6e-05,3e-07,-7.6e-12,7.7e-12,-5.4e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00031,0.00034,0.00034,0.00035,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,-7.6e-12,7.7e-12,-3.1e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6890000,0.71,0.0015,-0.014,0.71,-0.00021,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,-7.6e-12,7.7e-12,-3.6e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6990000,0.7,0.0016,-0.014,0.71,-0.00055,0.011,-0.12,0.004,0.0072,-3.7e+02,-1.6e-05,-5.6e-05,1.6e-07,-7.6e-12,7.7e-12,-6.6e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00035,0.00035,0.00023,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7090000,0.7,0.0016,-0.014,0.71,-0.0014,0.011,-0.13,0.0039,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,-7.6e-12,7.7e-12,-1e-05,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7190000,0.7,0.0016,-0.014,0.71,-0.0034,0.011,-0.15,0.0037,0.0093,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,-7.6e-12,7.7e-12,-8e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00036,0.00036,0.0002,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7290000,0.7,0.0016,-0.014,0.71,-0.0052,0.011,-0.15,0.0033,0.01,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,-7.6e-12,7.7e-12,-1.5e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00037,0.00037,0.00018,0.34,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7390000,0.7,0.0017,-0.014,0.71,-0.0056,0.012,-0.16,0.0027,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-07,-7.6e-12,7.7e-12,-1.6e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00038,0.00038,0.00017,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7490000,0.7,0.0017,-0.014,0.71,-0.0076,0.013,-0.16,0.002,0.013,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,-7.6e-12,7.7e-12,-2.4e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00039,0.00039,0.00016,0.4,0.4,0.15,0.76,0.76,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7590000,0.7,0.0017,-0.014,0.71,-0.0098,0.014,-0.17,0.0011,0.014,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-08,-7.6e-12,7.7e-12,-3.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00039,0.00039,0.00015,0.43,0.43,0.14,0.85,0.85,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7690000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.16,2.6e-05,0.015,-3.7e+02,-1.6e-05,-5.6e-05,-4.5e-08,-7.6e-12,7.7e-12,-5.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.0004,0.0004,0.00015,0.47,0.47,0.13,0.96,0.96,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7790000,0.7,0.0019,-0.014,0.71,-0.014,0.016,-0.16,-0.0013,0.017,-3.7e+02,-1.6e-05,-5.6e-05,-3.7e-07,-7.6e-12,7.7e-12,-7.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00041,0.00041,0.00014,0.51,0.51,0.12,1.1,1.1,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -7890000,0.7,0.0019,-0.014,0.71,-0.017,0.018,-0.16,-0.0028,0.018,-3.7e+02,-1.6e-05,-5.6e-05,-2.7e-07,-7.6e-12,7.7e-12,-9.8e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00042,0.00042,0.00014,0.55,0.55,0.11,1.2,1.2,0.1,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -7990000,0.7,0.0019,-0.014,0.71,-0.019,0.019,-0.16,-0.0046,0.02,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-07,-7.6e-12,7.7e-12,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00043,0.00043,0.00013,0.6,0.59,0.1,1.3,1.3,0.099,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -8090000,0.7,0.0019,-0.014,0.71,-0.021,0.02,-0.17,-0.0066,0.022,-3.7e+02,-1.6e-05,-5.6e-05,6.1e-08,-7.6e-12,7.7e-12,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00045,0.00045,0.00013,0.65,0.65,0.1,1.5,1.5,0.097,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 -8190000,0.7,0.0019,-0.014,0.71,-0.024,0.021,-0.18,-0.0088,0.023,-3.7e+02,-1.6e-05,-5.6e-05,-2.1e-07,-7.6e-12,7.7e-12,-0.00014,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00046,0.00046,0.00012,0.69,0.69,0.099,1.7,1.7,0.094,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 -8290000,0.7,0.002,-0.014,0.71,-0.026,0.022,-0.17,-0.011,0.025,-3.7e+02,-1.6e-05,-5.6e-05,-4e-07,-7.6e-12,7.7e-12,-0.00018,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00047,0.00047,0.00012,0.75,0.75,0.097,1.9,1.9,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0 -8390000,0.7,0.002,-0.014,0.71,-0.029,0.023,-0.17,-0.014,0.028,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,-7.6e-12,7.7e-12,-0.00021,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00048,0.00048,0.00012,0.81,0.81,0.097,2.1,2.1,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0 -8490000,0.7,0.002,-0.014,0.71,-0.031,0.025,-0.17,-0.017,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-3e-07,-7.6e-12,7.7e-12,-0.00025,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00049,0.00049,0.00012,0.87,0.87,0.096,2.3,2.3,0.089,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0 -8590000,0.7,0.002,-0.014,0.71,-0.034,0.027,-0.17,-0.021,0.032,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,-7.6e-12,7.7e-12,-0.0003,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00051,0.00051,0.00011,0.94,0.94,0.095,2.5,2.5,0.088,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0 -8690000,0.7,0.0021,-0.014,0.71,-0.037,0.028,-0.16,-0.024,0.033,-3.7e+02,-1.6e-05,-5.6e-05,-2.5e-07,-7.6e-12,7.7e-12,-0.00035,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00052,0.00052,0.00011,0.99,0.99,0.096,2.7,2.7,0.088,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0 -8790000,0.7,0.0021,-0.014,0.71,-0.04,0.03,-0.15,-0.028,0.036,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,-7.6e-12,7.7e-12,-0.00041,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00054,0.00054,0.00011,1.1,1.1,0.095,3,3,0.087,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0 -8890000,0.7,0.0021,-0.014,0.71,-0.043,0.03,-0.15,-0.032,0.038,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,-7.6e-12,7.7e-12,-0.00045,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00055,0.00055,0.00011,1.1,1.1,0.095,3.3,3.3,0.086,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0 -8990000,0.7,0.0021,-0.014,0.71,-0.045,0.031,-0.14,-0.036,0.04,-3.7e+02,-1.6e-05,-5.6e-05,-9.6e-07,-7.6e-12,7.7e-12,-0.00051,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00056,0.00056,0.00011,1.2,1.2,0.096,3.6,3.6,0.087,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0 -9090000,0.7,0.0022,-0.014,0.71,-0.048,0.031,-0.14,-0.04,0.042,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,-7.6e-12,7.7e-12,-0.00054,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00057,0.00057,0.00011,1.3,1.3,0.095,3.9,3.9,0.086,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0 -9190000,0.7,0.0022,-0.014,0.71,-0.05,0.032,-0.14,-0.045,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-5.2e-07,-7.6e-12,7.7e-12,-0.00057,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00059,0.00059,0.0001,1.4,1.4,0.094,4.3,4.3,0.085,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0 -9290000,0.7,0.0022,-0.014,0.71,-0.051,0.033,-0.14,-0.048,0.046,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,-7.6e-12,7.7e-12,-0.00061,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.0006,0.0006,0.0001,1.4,1.4,0.093,4.5,4.5,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0 -9390000,0.7,0.0022,-0.014,0.71,-0.053,0.035,-0.14,-0.054,0.049,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-07,-7.6e-12,7.7e-12,-0.00065,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00061,0.0001,1.5,1.5,0.093,5,5,0.086,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0 -9490000,0.7,0.0022,-0.014,0.71,-0.054,0.035,-0.13,-0.056,0.05,-3.7e+02,-1.6e-05,-5.6e-05,1.3e-08,-7.6e-12,7.7e-12,-0.00068,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00062,0.0001,1.6,1.6,0.091,5.2,5.2,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0 -9590000,0.7,0.0022,-0.014,0.71,-0.058,0.036,-0.13,-0.062,0.053,-3.7e+02,-1.6e-05,-5.6e-05,1.4e-07,-7.6e-12,7.7e-12,-0.00072,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,5.8,5.8,0.085,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0 -9690000,0.7,0.0022,-0.014,0.71,-0.058,0.037,-0.12,-0.065,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-4.4e-07,-7.6e-12,7.7e-12,-0.00077,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,6,6,0.086,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0 -9790000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.071,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-9.9e-08,-7.6e-12,7.7e-12,-0.00082,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00066,0.00066,0.0001,1.8,1.8,0.087,6.6,6.6,0.085,1.3e-08,1.3e-08,4.1e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0 -9890000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.073,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-1.8e-07,-7.6e-12,7.7e-12,-0.00085,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00066,0.00066,9.9e-05,1.8,1.8,0.084,6.8,6.8,0.085,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0 -9990000,0.7,0.0023,-0.014,0.71,-0.063,0.04,-0.1,-0.079,0.06,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,-7.6e-12,7.7e-12,-0.00089,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.9e-05,2,2,0.083,7.4,7.4,0.086,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0 -10090000,0.7,0.0023,-0.014,0.71,-0.061,0.039,-0.096,-0.079,0.059,-3.7e+02,-1.5e-05,-5.6e-05,-3.7e-07,-7.6e-12,7.7e-12,-0.00091,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00067,0.00067,9.8e-05,2,2,0.08,7.5,7.5,0.085,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0 -10190000,0.7,0.0023,-0.014,0.71,-0.064,0.042,-0.096,-0.086,0.063,-3.7e+02,-1.5e-05,-5.6e-05,-1.2e-06,-7.6e-12,7.7e-12,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00069,0.00069,9.8e-05,2.1,2.1,0.078,8.3,8.3,0.084,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 -10290000,0.7,0.0022,-0.014,0.71,-0.062,0.04,-0.083,-0.085,0.061,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,-7.6e-12,7.7e-12,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.8e-05,2.1,2.1,0.076,8.3,8.3,0.085,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 -10390000,0.7,0.0022,-0.014,0.71,0.0091,-0.019,0.0096,0.00085,-0.0017,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,-6.6e-10,4.8e-10,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.0007,9.7e-05,0.25,0.25,0.56,0.25,0.25,0.078,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0 -10490000,0.7,0.0023,-0.014,0.71,0.0074,-0.017,0.023,0.0017,-0.0036,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-1.7e-08,1.2e-08,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.26,0.26,0.55,0.26,0.26,0.08,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 -10590000,0.7,0.0024,-0.014,0.71,0.0069,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-2.7e-06,4.5e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.14,0.14,0.27,0.13,0.13,0.073,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 -10690000,0.7,0.0024,-0.014,0.71,0.0044,-0.0059,0.03,0.0024,-0.0015,-3.7e+02,-1.5e-05,-5.6e-05,-2.4e-06,-2.7e-06,4.7e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.7e-05,0.15,0.15,0.26,0.14,0.14,0.078,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -10790000,0.7,0.0024,-0.014,0.71,0.004,-0.0032,0.024,0.0026,-0.00073,-3.7e+02,-1.5e-05,-5.5e-05,-2.4e-06,-4.3e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.11,0.11,0.17,0.091,0.091,0.072,1.1e-08,1.1e-08,3.6e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -10890000,0.7,0.0024,-0.014,0.71,0.0023,-0.0019,0.02,0.0029,-0.00094,-3.7e+02,-1.5e-05,-5.5e-05,-2.5e-06,-4.3e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.6e-05,0.13,0.13,0.16,0.098,0.098,0.075,1.1e-08,1.1e-08,3.5e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -10990000,0.7,0.0023,-0.014,0.71,0.0052,0.0032,0.014,0.0046,-0.0022,-3.7e+02,-1.4e-05,-5.5e-05,-2e-06,-8.3e-06,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.00069,9.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,1.1e-08,1.1e-08,3.5e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0 -11090000,0.7,0.0023,-0.014,0.71,0.0035,0.0056,0.019,0.0051,-0.0018,-3.7e+02,-1.4e-05,-5.5e-05,-1.5e-06,-8.3e-06,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00072,0.00072,9.6e-05,0.13,0.13,0.11,0.08,0.08,0.074,1.1e-08,1.1e-08,3.4e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0 -11190000,0.7,0.0022,-0.014,0.71,0.0088,0.0081,0.0077,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-2e-06,-9.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00062,0.00062,9.6e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.4e-09,9.5e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 -11290000,0.7,0.0023,-0.014,0.71,0.0082,0.011,0.0074,0.0075,-0.0018,-3.7e+02,-1.3e-05,-5.5e-05,-2.7e-06,-9.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00064,0.00064,9.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.4e-09,9.5e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 -11390000,0.7,0.0023,-0.014,0.71,0.0037,0.009,0.0018,0.0054,-0.002,-3.7e+02,-1.4e-05,-5.5e-05,-3.2e-06,-5.3e-06,1.2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00054,0.00054,9.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 -11490000,0.7,0.0023,-0.014,0.71,0.00096,0.012,0.0026,0.0056,-0.00092,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5.3e-06,1.2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 -11590000,0.7,0.0022,-0.014,0.71,-0.0029,0.01,-0.0034,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-4.4e-06,-1e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11690000,0.7,0.0022,-0.014,0.71,-0.006,0.013,-0.0079,0.0039,-0.00027,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,-9.4e-07,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00047,0.00047,9.6e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.0097,0.0017,0.00056,-3.7e+02,-1.4e-05,-5.6e-05,-4.8e-06,1.5e-07,9.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00039,0.00039,9.6e-05,0.096,0.096,0.039,0.052,0.052,0.063,6.6e-09,6.6e-09,3e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.011,0.00052,0.0019,-3.7e+02,-1.4e-05,-5.6e-05,-5.3e-06,9.1e-08,9.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0004,0.0004,9.6e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.6e-09,6.6e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.016,-0.0004,0.0023,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,1.5e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00034,0.00034,9.6e-05,0.09,0.09,0.033,0.051,0.051,0.061,5.9e-09,5.9e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -12090000,0.7,0.0022,-0.014,0.71,-0.016,0.016,-0.022,-0.0019,0.0038,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,1.7e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00035,0.00035,9.6e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.9e-09,5.9e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -12190000,0.7,0.0018,-0.014,0.71,-0.0089,0.013,-0.017,0.0014,0.0019,-3.7e+02,-1.3e-05,-5.7e-05,-4.5e-06,4.4e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0003,0.0003,9.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.4e-09,5.4e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -12290000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.016,0.00035,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-4.3e-06,4.2e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00031,0.00031,9.6e-05,0.1,0.1,0.028,0.059,0.059,0.059,5.4e-09,5.4e-09,2.7e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -12390000,0.7,0.0015,-0.014,0.71,-0.0059,0.011,-0.015,0.0029,0.0017,-3.7e+02,-1.3e-05,-5.8e-05,-4.6e-06,5.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00027,0.00027,9.5e-05,0.079,0.079,0.026,0.05,0.05,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0 -12490000,0.7,0.0015,-0.014,0.71,-0.0072,0.013,-0.018,0.0023,0.0029,-3.7e+02,-1.3e-05,-5.8e-05,-5.1e-06,5.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00028,0.00028,9.5e-05,0.092,0.092,0.026,0.059,0.059,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0 -12590000,0.7,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.0028,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-5e-06,7.4e-06,1.7e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00025,0.00025,9.5e-05,0.073,0.073,0.025,0.05,0.05,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0 -12690000,0.7,0.0016,-0.014,0.71,-0.015,0.012,-0.027,-0.0043,0.0026,-3.7e+02,-1.3e-05,-5.8e-05,-5.2e-06,7.6e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00026,0.00026,9.5e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0 -12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0092,-0.03,-0.0077,0.0013,-3.7e+02,-1.4e-05,-5.8e-05,-5e-06,8.1e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.7e-07,0,0,0,0,0,0,0,0 -12890000,0.7,0.0016,-0.013,0.71,-0.021,0.0091,-0.029,-0.0097,0.0022,-3.7e+02,-1.4e-05,-5.8e-05,-4.8e-06,7.4e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00024,0.00024,9.5e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0 -12990000,0.7,0.0012,-0.014,0.71,-0.0088,0.0066,-0.03,-0.0011,0.0012,-3.7e+02,-1.3e-05,-5.9e-05,-4.2e-06,7.3e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.5e-05,0.064,0.064,0.025,0.049,0.049,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0 -13090000,0.7,0.0012,-0.014,0.71,-0.0096,0.0068,-0.03,-0.002,0.0018,-3.7e+02,-1.3e-05,-5.9e-05,-4.7e-06,7e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.073,0.073,0.025,0.057,0.057,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0 -13190000,0.7,0.00099,-0.014,0.71,-0.00038,0.0062,-0.027,0.0044,0.0012,-3.7e+02,-1.2e-05,-5.9e-05,-4.6e-06,5.6e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0 -13290000,0.7,0.001,-0.014,0.71,-0.00065,0.007,-0.024,0.0043,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-4.1e-06,4.3e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.4e-05,0.068,0.069,0.027,0.057,0.057,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0 -13390000,0.7,0.00085,-0.014,0.71,0.00026,0.006,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-3.6e-06,2.6e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.8e-07,0,0,0,0,0,0,0,0 -13490000,0.7,0.00087,-0.014,0.71,-0.00025,0.0059,-0.019,0.0033,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-3.1e-06,1.8e-06,2.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00021,9.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.7e-07,0,0,0,0,0,0,0,0 -13590000,0.7,0.00081,-0.014,0.71,7.7e-05,0.0061,-0.021,0.0024,0.001,-3.7e+02,-1.2e-05,-5.9e-05,-3.4e-06,1.5e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0 -13690000,0.7,0.00079,-0.014,0.71,0.00075,0.0078,-0.025,0.0024,0.0017,-3.7e+02,-1.1e-05,-5.9e-05,-2.7e-06,1.8e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.061,0.061,0.029,0.056,0.056,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0 -13790000,0.7,0.00067,-0.014,0.71,0.0014,0.0036,-0.027,0.0035,-0.00062,-3.7e+02,-1.1e-05,-6e-05,-2.7e-06,-2.9e-07,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.3e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0 -13890000,0.7,0.00063,-0.014,0.71,0.0019,0.0035,-0.031,0.0036,-0.00029,-3.7e+02,-1.1e-05,-6e-05,-2.3e-06,1.4e-08,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.3e-05,0.058,0.058,0.03,0.056,0.056,0.05,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0 -13990000,0.7,0.00056,-0.014,0.71,0.0022,0.001,-0.03,0.0045,-0.002,-3.7e+02,-1.1e-05,-6e-05,-2.2e-06,-2.6e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.049,0.049,0.03,0.048,0.048,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0 -14090000,0.7,0.00054,-0.014,0.71,0.0023,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-1.5e-06,-2.5e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.055,0.055,0.031,0.056,0.056,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.3e-07,0,0,0,0,0,0,0,0 -14190000,0.7,0.00044,-0.014,0.71,0.0057,0.00062,-0.033,0.0068,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.1e-06,-2.3e-06,1.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.047,0.047,0.031,0.048,0.048,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0 -14290000,0.7,0.00045,-0.014,0.71,0.0065,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-8.2e-07,-3e-06,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.053,0.053,0.032,0.055,0.055,0.051,3.1e-09,3.1e-09,1.7e-09,3.6e-06,3.6e-06,6.7e-07,0,0,0,0,0,0,0,0 -14390000,0.7,0.00036,-0.014,0.71,0.0083,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-1.5e-07,-3e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,1.7e-09,3.6e-06,3.6e-06,6.3e-07,0,0,0,0,0,0,0,0 -14490000,0.7,0.00034,-0.013,0.71,0.0083,0.0035,-0.037,0.0095,-0.001,-3.7e+02,-1e-05,-6e-05,7.6e-08,-2.5e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.051,0.051,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,1.6e-09,3.6e-06,3.6e-06,6.2e-07,0,0,0,0,0,0,0,0 -14590000,0.7,0.00033,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-1.1e-05,-6.1e-05,1.4e-07,-6.2e-06,1.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.2e-05,0.044,0.044,0.031,0.047,0.047,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0 -14690000,0.7,0.00029,-0.013,0.71,0.0062,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-1.1e-05,-6.1e-05,6.2e-07,-7.3e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.6e-07,0,0,0,0,0,0,0,0 -14790000,0.7,0.00031,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-1.1e-05,-6.1e-05,7.8e-07,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.1e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0 -14890000,0.7,0.00031,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-1.1e-05,-6.1e-05,1.1e-06,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.1e-05,0.048,0.048,0.031,0.054,0.054,0.052,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.1e-07,0,0,0,0,0,0,0,0 -14990000,0.7,0.0003,-0.013,0.71,0.0034,-0.0019,-0.029,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.2e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.042,0.042,0.03,0.047,0.047,0.051,2.4e-09,2.4e-09,1.5e-09,3.5e-06,3.5e-06,4.8e-07,0,0,0,0,0,0,0,0 -15090000,0.7,0.00023,-0.013,0.71,0.0038,-0.0021,-0.031,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.1e-05,2.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.4e-09,2.4e-09,1.4e-09,3.5e-06,3.5e-06,4.6e-07,0,0,0,0,0,0,0,0 -15190000,0.7,0.00025,-0.013,0.71,0.0032,-0.00083,-0.029,0.0028,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.041,0.041,0.03,0.047,0.047,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.3e-07,0,0,0,0,0,0,0,0 -15290000,0.7,0.0002,-0.013,0.71,0.0038,-0.00068,-0.027,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.2e-05,2.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9e-05,0.046,0.046,0.03,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.2e-07,0,0,0,0,0,0,0,0 -15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00032,-0.024,0.00054,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.029,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.9e-07,0,0,0,0,0,0,0,0 -15490000,0.7,0.00023,-0.013,0.71,0.0043,-0.00071,-0.024,0.00091,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9e-05,0.045,0.045,0.029,0.053,0.053,0.053,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0 -15590000,0.7,0.00024,-0.013,0.71,0.0024,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.3e-09,3.5e-06,3.5e-06,3.5e-07,0,0,0,0,0,0,0,0 -15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00087,-0.023,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00018,8.9e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0 -15790000,0.7,0.00021,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00098,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,8.9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3.1e-07,0,0,0,0,0,0,0,0 -15890000,0.7,0.00016,-0.013,0.71,0.0042,-0.003,-0.024,-0.00058,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3e-07,0,0,0,0,0,0,0,0 -15990000,0.7,0.0001,-0.013,0.71,0.004,-0.0039,-0.019,-0.00066,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.7e-09,1.7e-09,1.2e-09,3.4e-06,3.4e-06,2.8e-07,0,0,0,0,0,0,0,0 -16090000,0.71,0.0001,-0.013,0.71,0.0058,-0.0042,-0.016,-0.00019,-0.0043,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.8e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.7e-09,1.7e-09,1.1e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0 -16190000,0.71,0.00013,-0.013,0.71,0.0057,-0.0034,-0.014,-0.0004,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.8e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.5e-07,0,0,0,0,0,0,0,0 -16290000,0.71,0.00014,-0.013,0.71,0.0074,-0.0042,-0.016,0.00026,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0 -16390000,0.71,0.00013,-0.013,0.71,0.0063,-0.0044,-0.015,-6.7e-05,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1.1e-09,3.3e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0 -16490000,0.71,0.00015,-0.013,0.71,0.0055,-0.0039,-0.018,0.00049,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.7e-05,0.042,0.042,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1e-09,3.3e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0 -16590000,0.71,0.00041,-0.013,0.71,0.0019,-0.0012,-0.018,-0.0025,-7.8e-05,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-8.9e-06,4.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00016,0.00016,8.7e-05,0.037,0.037,0.022,0.046,0.046,0.051,1.3e-09,1.3e-09,1e-09,3.3e-06,3.3e-06,2e-07,0,0,0,0,0,0,0,0 -16690000,0.71,0.0004,-0.013,0.71,0.0021,-0.00073,-0.015,-0.0023,-0.00017,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-9.5e-06,4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00016,8.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.3e-09,1.3e-09,9.9e-10,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0 -16790000,0.71,0.00055,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0047,0.0025,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-3.8e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.2e-09,1.2e-09,9.7e-10,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0 -16890000,0.71,0.00056,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-4.2e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.6e-05,0.041,0.041,0.021,0.052,0.052,0.051,1.2e-09,1.2e-09,9.5e-10,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0 -16990000,0.71,0.0005,-0.013,0.71,-0.0016,0.00034,-0.01,-0.0052,0.00086,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-8.3e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.036,0.036,0.02,0.046,0.046,0.05,1.1e-09,1.1e-09,9.2e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0 -17090000,0.71,0.00047,-0.013,0.71,-0.00076,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-1.3e-05,-6e-05,3e-06,-8.2e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.6e-05,0.04,0.04,0.02,0.052,0.052,0.05,1.1e-09,1.1e-09,9e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0 -17190000,0.71,0.00046,-0.013,0.71,-0.00031,0.0013,-0.011,-0.0057,-0.00054,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.6e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,8.9e-10,3.2e-06,3.2e-06,1.5e-07,0,0,0,0,0,0,0,0 -17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0066,-0.0056,-0.00038,-3.7e+02,-1.4e-05,-6e-05,3e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.5e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,8.7e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0 -17390000,0.71,0.0004,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00014,8.5e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,8.5e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0 -17490000,0.71,0.00039,-0.013,0.71,0.003,0.001,-0.0029,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0 -17590000,0.71,0.0003,-0.013,0.71,0.0042,-0.00014,0.0026,-0.0037,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.4e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.9e-10,7.9e-10,8.1e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0 -17690000,0.71,0.00027,-0.012,0.71,0.0051,0.00057,0.002,-0.0032,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.6e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.9e-10,7.9e-10,7.9e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0 -17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00029,0.00064,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0 -17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00047,0.00074,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0 -17990000,0.71,0.00014,-0.013,0.71,0.011,-0.0022,0.002,-0.00052,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,7.5e-10,3.1e-06,3.1e-06,1e-07,0,0,0,0,0,0,0,0 -18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0024,0.0043,0.00061,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,7.3e-10,3.1e-06,3.1e-06,9.7e-08,0,0,0,0,0,0,0,0 -18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0057,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,7.2e-10,3.1e-06,3.1e-06,9.2e-08,0,0,0,0,0,0,0,0 -18290000,0.71,4.9e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,8.9e-08,0,0,0,0,0,0,0,0 -18390000,0.71,6.5e-05,-0.013,0.71,0.014,-0.0002,0.008,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.4e-08,0,0,0,0,0,0,0,0 -18490000,0.71,8e-05,-0.012,0.71,0.014,0.00021,0.0077,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.2e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8.2e-08,0,0,0,0,0,0,0,0 -18590000,0.71,8.5e-05,-0.012,0.71,0.013,0.00045,0.0058,0.0035,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.8e-08,0,0,0,0,0,0,0,0 -18690000,0.71,5.4e-05,-0.012,0.71,0.014,-0.00024,0.0039,0.0049,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00013,0.00012,8.2e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.5e-10,3.1e-06,3.1e-06,7.5e-08,0,0,0,0,0,0,0,0 -18790000,0.71,8.4e-05,-0.012,0.71,0.012,6.6e-05,0.0036,0.0038,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.2e-08,0,0,0,0,0,0,0,0 -18890000,0.71,0.00011,-0.012,0.71,0.013,0.00056,0.0042,0.005,-0.00085,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,7e-08,0,0,0,0,0,0,0,0 -18990000,0.71,9.5e-05,-0.012,0.71,0.014,0.0015,0.0029,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0 -19090000,0.71,7.9e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0078,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.5e-08,0,0,0,0,0,0,0,0 -19190000,0.71,8.2e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00045,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00011,8.1e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,5.9e-10,3e-06,3e-06,6.2e-08,0,0,0,0,0,0,0,0 -19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00026,-3.7e+02,-1.4e-05,-6.1e-05,5.1e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00012,8e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,6e-08,0,0,0,0,0,0,0,0 -19390000,0.71,0.00012,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.3e-10,3.3e-10,5.6e-10,3e-06,3e-06,5.8e-08,0,0,0,0,0,0,0,0 -19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00032,0.0088,0.0092,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.6e-08,0,0,0,0,0,0,0,0 -19590000,0.71,0.00019,-0.012,0.71,0.0097,-0.0013,0.0081,0.0075,-0.0003,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,3e-06,3e-06,5.4e-08,0,0,0,0,0,0,0,0 -19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0096,0.0085,-0.00055,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0 -19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0076,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,6.1e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0062,-0.00076,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20090000,0.71,0.00018,-0.012,0.71,0.0039,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,7.1e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.6e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20290000,0.71,0.00025,-0.012,0.71,0.00038,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.6e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.8e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20390000,0.71,0.00027,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.4e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20490000,0.71,0.00032,-0.012,0.71,-0.0025,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.4e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.027,0.027,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,4.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20590000,0.71,0.00034,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-1.4e-05,-6e-05,7.1e-06,-1.3e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0094,0.044,0.044,0.04,2e-10,2e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.2e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.7e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20890000,0.71,0.00039,-0.012,0.71,-0.0037,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,0.0001,0.0001,7.7e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-8.6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -21090000,0.71,0.00039,-0.012,0.71,-0.0041,-0.017,0.015,0.0023,-0.0047,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-8.6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.9e-05,9.9e-05,7.7e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -21190000,0.71,0.00042,-0.012,0.71,-0.0033,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-6.2e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-6.2e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.6e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0029,-0.0034,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-2.5e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.6e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-2.5e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.7e-05,9.6e-05,7.6e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,9.1e-07,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21690000,0.71,0.00055,-0.012,0.71,-0.0057,-0.016,0.017,0.0014,-0.0048,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,8.9e-07,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,9.1e-05,-0.00074,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,6.1e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.4e-05,9.4e-05,7.5e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21890000,0.71,0.00057,-0.012,0.71,-0.0063,-0.012,0.016,-0.00054,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.4e-05,7.5e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.3e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22090000,0.71,0.00064,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0021,0.00064,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.3e-05,7.5e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22190000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.00059,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.2e-05,9.2e-05,7.5e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22290000,0.71,0.00065,-0.012,0.71,-0.0082,-0.0081,0.015,-0.0025,-0.00018,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.2e-05,7.4e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22390000,0.71,0.00062,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00017,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.4e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22490000,0.71,0.00063,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0031,-0.00094,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.2e-05,9.2e-05,7.4e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.00014,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0067,0.018,-0.0043,-0.00054,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9.1e-05,7.4e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00043,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0051,0.021,-0.0066,-0.00097,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0086,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.6e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.8e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23790000,0.71,0.005,0.00066,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -23990000,0.71,0.00097,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.6e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24090000,0.71,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-11,6.8e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.1e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.6e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-11,6.5e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24490000,0.71,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.4e-05,3.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.4e-05,8.4e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2.5e-05,3.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.4e-05,2.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3.4e-05,2.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.3e-05,7e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.3e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,5.9e-06,3.3e-05,3.4e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.2e-05,3.5e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.9e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.6e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.8e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.7e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8e-05,6.9e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.1e-06,3.3e-05,-4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,3.4e-05,-4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.6e-05,-8.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,4.6e-05,-8.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,5.9e-06,3.3e-05,-9.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.8e-06,3.3e-05,-9.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.5e-06,4.3e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.7e-05,6.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.6e-06,4.2e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.4e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.8e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.4e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.4e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.3e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.6e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27390000,0.71,0.037,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.2e-06,-5.9e-05,5.5e-06,5.9e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.7e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.4e-06,5.8e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.5e-06,5.7e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.4e-06,5.6e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,5.8e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.2e-06,5.6e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.3e-06,5.1e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5.1e-06,5e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5.1e-06,4.7e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,4.9e-06,4.6e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.3e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.7e-05,6.5e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,4e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28590000,0.71,0.00085,0.001,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.7e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28690000,0.71,0.00014,8.4e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,3.2e-05,-0.0001,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28790000,0.71,-0.00015,-0.00016,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,1.2e-06,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28890000,0.71,-0.00017,5.5e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,-3.2e-06,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -28990000,0.71,2.7e-05,0.0005,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.5e-06,-2.4e-05,-0.00025,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -29090000,0.71,0.00018,0.00091,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.4e-06,-2.9e-05,-0.00023,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -29190000,0.71,0.0004,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.4e-06,-4.9e-05,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -29290000,0.71,0.00075,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.3e-06,-5.5e-05,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-7e-05,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.16,0.16,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.7e-05,4.1e-06,-7.5e-05,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-9.8e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.0091,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.9e-06,-0.00012,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.3e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.7e-06,-0.00013,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00015,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00015,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00017,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00017,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30390000,0.71,0.003,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00018,-0.00023,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30590000,0.71,0.0029,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.0002,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.0002,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30790000,0.71,0.0027,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30990000,0.71,0.0025,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00022,-0.00018,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00023,-0.00017,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31290000,0.71,0.002,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00025,-0.00013,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31390000,0.71,0.0018,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00025,-0.00011,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00026,-9.8e-05,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31590000,0.71,0.0016,0.0024,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-8.1e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-6.9e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00028,-5.1e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31890000,0.71,0.00088,0.00039,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00029,-3.8e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -31990000,0.71,0.00075,-7e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-1.9e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -32090000,0.71,0.00046,-0.00079,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-3.9e-06,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -32190000,0.71,0.00025,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00031,1.7e-05,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32290000,0.71,1.5e-05,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3.3e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32390000,0.71,-0.00017,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,4.2e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00033,5.3e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32590000,0.71,-0.00028,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,6e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,6.6e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,5.9e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32790000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,7.5e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,8.6e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32990000,0.71,-6.8e-05,-0.0033,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,9.9e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33090000,0.71,-0.0001,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.0001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,8e-05,7.4e-05,6.1e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,7.9e-05,7.5e-05,6.5e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33490000,0.41,0.0069,0.00073,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5e-05,7.8e-05,7.7e-05,7e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33590000,0.25,0.001,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,7.6e-05,7.8e-05,7.3e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.5e-05,8e-05,7.6e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.4e-05,7.2e-05,8e-05,7.6e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.8e-05,6.9e-05,7.8e-05,7.2e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34090000,-0.5,-0.002,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00013,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.1e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34290000,-0.61,-0.0023,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,6.5e-05,7.3e-05,6.5e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34390000,-0.64,-0.0025,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.048,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34790000,-0.67,-0.0021,-0.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34890000,-0.68,-0.0021,-0.0016,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34990000,-0.68,-0.0085,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.057,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35290000,-0.68,-0.0085,-0.0045,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +6390000,0.71,0.0014,-0.014,0.71,-0.0082,0.0057,-0.05,0.0016,0.0016,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,-7.6e-12,7.7e-12,-3.5e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +6490000,0.71,0.0014,-0.014,0.71,-0.0087,0.0064,-0.052,0.00072,0.0022,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,-7.6e-12,7.7e-12,-4e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +6590000,0.71,0.0015,-0.014,0.71,-0.0095,0.0065,-0.099,-0.00016,0.0028,-3.7e+02,-1.6e-05,-5.6e-05,3.6e-07,-7.6e-12,7.7e-12,-2.2e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00039,0.00034,0.00034,0.00043,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +6690000,0.7,0.0015,-0.014,0.71,-0.0093,0.0076,-0.076,-0.0011,0.0035,-3.7e+02,-1.6e-05,-5.6e-05,3e-07,-7.6e-12,7.7e-12,-5.4e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00031,0.00034,0.00034,0.00035,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +6790000,0.71,0.0015,-0.014,0.71,-0.011,0.0075,-0.11,-0.0021,0.0043,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,-7.6e-12,7.7e-12,-3.1e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +6890000,0.71,0.0015,-0.014,0.71,-0.013,0.0081,-0.12,-0.0033,0.0051,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,-7.6e-12,7.7e-12,-3.6e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +6990000,0.7,0.0016,-0.014,0.71,-0.014,0.009,-0.12,-0.0047,0.0059,-3.7e+02,-1.6e-05,-5.6e-05,1.6e-07,-7.6e-12,7.7e-12,-6.6e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00035,0.00035,0.00023,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +7090000,0.7,0.0016,-0.014,0.71,-0.014,0.0086,-0.13,-0.0061,0.0068,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,-7.6e-12,7.7e-12,-1e-05,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +7190000,0.7,0.0016,-0.014,0.71,-0.016,0.0088,-0.15,-0.0076,0.0076,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-07,-7.6e-12,7.7e-12,-8e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00036,0.00036,0.0002,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 +7290000,0.7,0.0016,-0.014,0.71,-0.018,0.009,-0.15,-0.0093,0.0085,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,-7.6e-12,7.7e-12,-1.5e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00037,0.00037,0.00018,0.34,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 +7390000,0.7,0.0017,-0.014,0.71,-0.019,0.011,-0.16,-0.011,0.0094,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-07,-7.6e-12,7.7e-12,-1.6e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00038,0.00038,0.00017,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 +7490000,0.7,0.0017,-0.014,0.71,-0.02,0.011,-0.16,-0.013,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,-7.6e-12,7.7e-12,-2.4e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00039,0.00039,0.00016,0.4,0.4,0.15,0.76,0.76,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 +7590000,0.7,0.0018,-0.014,0.71,-0.023,0.012,-0.17,-0.015,0.012,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-08,-7.6e-12,7.7e-12,-3.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00039,0.00039,0.00015,0.43,0.43,0.14,0.85,0.85,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 +7690000,0.7,0.0018,-0.014,0.71,-0.025,0.013,-0.16,-0.017,0.013,-3.7e+02,-1.6e-05,-5.6e-05,-4.5e-08,-7.6e-12,7.7e-12,-5.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.0004,0.0004,0.00015,0.47,0.47,0.13,0.96,0.96,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 +7790000,0.7,0.0019,-0.014,0.71,-0.026,0.014,-0.16,-0.02,0.014,-3.7e+02,-1.6e-05,-5.6e-05,-3.7e-07,-7.6e-12,7.7e-12,-7.3e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00041,0.00041,0.00014,0.51,0.51,0.12,1.1,1.1,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 +7890000,0.7,0.0019,-0.014,0.71,-0.03,0.016,-0.16,-0.023,0.015,-3.7e+02,-1.6e-05,-5.6e-05,-2.7e-07,-7.6e-12,7.7e-12,-9.8e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00042,0.00042,0.00014,0.55,0.55,0.11,1.2,1.2,0.1,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 +7990000,0.7,0.0019,-0.014,0.71,-0.032,0.017,-0.16,-0.025,0.017,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-07,-7.6e-12,7.7e-12,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00043,0.00043,0.00013,0.6,0.59,0.1,1.3,1.3,0.099,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 +8090000,0.7,0.0019,-0.014,0.71,-0.034,0.018,-0.17,-0.029,0.018,-3.7e+02,-1.6e-05,-5.6e-05,5.8e-08,-7.6e-12,7.7e-12,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00045,0.00045,0.00013,0.65,0.65,0.1,1.5,1.5,0.097,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 +8190000,0.7,0.0019,-0.014,0.71,-0.037,0.02,-0.18,-0.032,0.02,-3.7e+02,-1.6e-05,-5.6e-05,-2.1e-07,-7.6e-12,7.7e-12,-0.00014,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00046,0.00046,0.00012,0.69,0.69,0.099,1.7,1.7,0.094,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 +8290000,0.7,0.002,-0.014,0.71,-0.039,0.021,-0.17,-0.036,0.022,-3.7e+02,-1.6e-05,-5.6e-05,-4.1e-07,-7.6e-12,7.7e-12,-0.00018,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00047,0.00047,0.00012,0.75,0.75,0.097,1.9,1.9,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0 +8390000,0.7,0.002,-0.014,0.71,-0.041,0.022,-0.17,-0.04,0.024,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-07,-7.6e-12,7.7e-12,-0.00021,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00048,0.00048,0.00012,0.81,0.81,0.097,2.1,2.1,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0 +8490000,0.7,0.002,-0.014,0.71,-0.043,0.023,-0.17,-0.043,0.025,-3.7e+02,-1.6e-05,-5.6e-05,-3.1e-07,-7.6e-12,7.7e-12,-0.00025,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00049,0.00049,0.00012,0.87,0.87,0.096,2.3,2.3,0.089,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0 +8590000,0.7,0.002,-0.014,0.71,-0.046,0.026,-0.17,-0.048,0.028,-3.7e+02,-1.6e-05,-5.6e-05,-6.3e-07,-7.6e-12,7.7e-12,-0.0003,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00051,0.00051,0.00011,0.94,0.94,0.095,2.5,2.5,0.088,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0 +8690000,0.7,0.0021,-0.014,0.71,-0.049,0.027,-0.16,-0.052,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-2.6e-07,-7.6e-12,7.7e-12,-0.00035,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00052,0.00052,0.00011,0.99,0.99,0.096,2.7,2.7,0.088,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0 +8790000,0.7,0.0021,-0.014,0.71,-0.052,0.028,-0.15,-0.057,0.032,-3.7e+02,-1.6e-05,-5.6e-05,-4.8e-07,-7.6e-12,7.7e-12,-0.00041,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00054,0.00054,0.00011,1.1,1.1,0.095,3,3,0.087,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0 +8890000,0.7,0.0021,-0.014,0.71,-0.054,0.029,-0.15,-0.061,0.033,-3.7e+02,-1.6e-05,-5.6e-05,-6.4e-07,-7.6e-12,7.7e-12,-0.00045,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00055,0.00055,0.00011,1.1,1.1,0.095,3.3,3.3,0.086,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0 +8990000,0.7,0.0022,-0.014,0.71,-0.056,0.03,-0.14,-0.067,0.036,-3.7e+02,-1.6e-05,-5.6e-05,-9.9e-07,-7.6e-12,7.7e-12,-0.00051,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00056,0.00056,0.00011,1.2,1.2,0.096,3.6,3.6,0.087,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0 +9090000,0.7,0.0022,-0.014,0.71,-0.058,0.03,-0.14,-0.07,0.038,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,-7.6e-12,7.7e-12,-0.00054,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00057,0.00057,0.00011,1.3,1.3,0.095,3.9,3.9,0.086,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0 +9190000,0.7,0.0022,-0.014,0.71,-0.06,0.031,-0.14,-0.076,0.04,-3.7e+02,-1.6e-05,-5.6e-05,-5.6e-07,-7.6e-12,7.7e-12,-0.00057,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00059,0.00059,0.0001,1.4,1.4,0.094,4.3,4.3,0.085,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0 +9290000,0.7,0.0022,-0.014,0.71,-0.061,0.032,-0.14,-0.079,0.042,-3.7e+02,-1.6e-05,-5.6e-05,-5.2e-07,-7.6e-12,7.7e-12,-0.00061,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.0006,0.0006,0.0001,1.4,1.4,0.093,4.5,4.5,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0 +9390000,0.7,0.0022,-0.014,0.71,-0.063,0.035,-0.14,-0.085,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-5.6e-07,-7.6e-12,7.7e-12,-0.00065,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00061,0.0001,1.5,1.5,0.093,5,5,0.086,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0 +9490000,0.7,0.0022,-0.014,0.71,-0.063,0.035,-0.13,-0.088,0.046,-3.7e+02,-1.6e-05,-5.6e-05,-5.2e-08,-7.6e-12,7.7e-12,-0.00068,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00062,0.0001,1.6,1.6,0.091,5.2,5.2,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0 +9590000,0.7,0.0022,-0.014,0.71,-0.066,0.036,-0.13,-0.094,0.049,-3.7e+02,-1.6e-05,-5.6e-05,6.1e-08,-7.6e-12,7.7e-12,-0.00072,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,5.8,5.8,0.085,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0 +9690000,0.7,0.0023,-0.014,0.71,-0.066,0.038,-0.12,-0.096,0.049,-3.7e+02,-1.6e-05,-5.6e-05,-5.3e-07,-7.6e-12,7.7e-12,-0.00077,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,6,6,0.086,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0 +9790000,0.7,0.0023,-0.014,0.71,-0.067,0.04,-0.11,-0.1,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-2e-07,-7.6e-12,7.7e-12,-0.00082,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00066,0.00066,0.0001,1.8,1.8,0.087,6.6,6.6,0.085,1.3e-08,1.3e-08,4.1e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0 +9890000,0.7,0.0023,-0.014,0.71,-0.066,0.041,-0.11,-0.1,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-2.9e-07,-7.6e-12,7.7e-12,-0.00085,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00066,0.00066,9.9e-05,1.8,1.8,0.084,6.8,6.8,0.085,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0 +9990000,0.7,0.0023,-0.014,0.71,-0.069,0.042,-0.1,-0.11,0.057,-3.7e+02,-1.6e-05,-5.6e-05,-6e-07,-7.6e-12,7.7e-12,-0.00089,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.9e-05,2,2,0.083,7.4,7.4,0.086,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0 +10090000,0.7,0.0023,-0.014,0.71,-0.066,0.041,-0.096,-0.11,0.057,-3.7e+02,-1.5e-05,-5.6e-05,-5.2e-07,-7.6e-12,7.7e-12,-0.00091,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00067,0.00067,9.8e-05,2,2,0.08,7.5,7.5,0.085,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0 +10190000,0.7,0.0023,-0.014,0.71,-0.068,0.044,-0.096,-0.12,0.061,-3.7e+02,-1.5e-05,-5.6e-05,-1.4e-06,-7.6e-12,7.7e-12,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00069,0.00069,9.8e-05,2.1,2.1,0.078,8.3,8.3,0.084,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 +10290000,0.7,0.0023,-0.014,0.71,-0.066,0.043,-0.083,-0.11,0.059,-3.7e+02,-1.5e-05,-5.5e-05,-1.9e-06,-7.6e-12,7.7e-12,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.8e-05,2.1,2.1,0.076,8.3,8.3,0.085,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 +10390000,0.7,0.0022,-0.014,0.71,0.0093,-0.019,0.0096,0.00086,-0.0017,-3.7e+02,-1.5e-05,-5.5e-05,-1.9e-06,-6.7e-10,4.9e-10,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.0007,9.7e-05,0.25,0.25,0.56,0.25,0.25,0.078,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0 +10490000,0.7,0.0023,-0.014,0.71,0.0077,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-1.5e-05,-5.5e-05,-2.5e-06,-1.7e-08,1.3e-08,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.26,0.26,0.55,0.26,0.26,0.08,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 +10590000,0.7,0.0024,-0.014,0.71,0.0073,-0.0061,0.026,0.0018,-0.00081,-3.7e+02,-1.5e-05,-5.5e-05,-2.5e-06,-2.6e-06,3.9e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.14,0.14,0.27,0.13,0.13,0.073,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 +10690000,0.7,0.0025,-0.014,0.71,0.005,-0.0053,0.03,0.0025,-0.0014,-3.7e+02,-1.5e-05,-5.5e-05,-2.7e-06,-2.6e-06,4e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.7e-05,0.15,0.15,0.26,0.14,0.14,0.078,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 +10790000,0.7,0.0024,-0.014,0.71,0.0045,-0.0025,0.024,0.0027,-0.00071,-3.7e+02,-1.5e-05,-5.5e-05,-2.7e-06,-4e-06,1.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.11,0.11,0.17,0.091,0.091,0.072,1.1e-08,1.1e-08,3.6e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 +10890000,0.7,0.0024,-0.014,0.71,0.003,-0.001,0.02,0.003,-0.00085,-3.7e+02,-1.5e-05,-5.5e-05,-2.8e-06,-4e-06,1.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.6e-05,0.13,0.13,0.16,0.098,0.098,0.075,1.1e-08,1.1e-08,3.5e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 +10990000,0.7,0.0023,-0.014,0.71,0.0058,0.0039,0.014,0.0047,-0.0022,-3.7e+02,-1.4e-05,-5.5e-05,-2.3e-06,-7.7e-06,8.4e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.00069,9.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,1.1e-08,1.1e-08,3.5e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0 +11090000,0.7,0.0024,-0.014,0.71,0.0043,0.0066,0.019,0.0052,-0.0017,-3.7e+02,-1.4e-05,-5.5e-05,-1.9e-06,-7.8e-06,8.4e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00072,0.00072,9.6e-05,0.13,0.13,0.11,0.08,0.08,0.074,1.1e-08,1.1e-08,3.4e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0 +11190000,0.7,0.0022,-0.014,0.71,0.0094,0.0089,0.0077,0.0066,-0.0027,-3.7e+02,-1.3e-05,-5.5e-05,-2.3e-06,-8.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00062,0.00062,9.6e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.4e-09,9.5e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 +11290000,0.7,0.0023,-0.014,0.71,0.0089,0.011,0.0074,0.0076,-0.0017,-3.7e+02,-1.3e-05,-5.5e-05,-3e-06,-8.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00064,0.00064,9.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.4e-09,9.5e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 +11390000,0.7,0.0023,-0.014,0.71,0.0043,0.0098,0.0018,0.0054,-0.0019,-3.7e+02,-1.4e-05,-5.5e-05,-3.6e-06,-3.9e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00054,0.00054,9.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 +11490000,0.7,0.0023,-0.014,0.71,0.0016,0.013,0.0026,0.0057,-0.00077,-3.7e+02,-1.4e-05,-5.5e-05,-4.6e-06,-3.9e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 +11590000,0.7,0.0022,-0.014,0.71,-0.0024,0.011,-0.0034,0.0044,-0.0013,-3.7e+02,-1.4e-05,-5.6e-05,-4.8e-06,6.8e-07,9.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +11690000,0.7,0.0022,-0.014,0.71,-0.0054,0.014,-0.0079,0.004,-0.00014,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,7.8e-07,9.8e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00047,0.00047,9.6e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.0097,0.0018,0.00062,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,2.1e-06,8.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00039,0.00039,9.6e-05,0.096,0.096,0.039,0.052,0.052,0.063,6.6e-09,6.6e-09,3e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +11890000,0.7,0.0022,-0.014,0.71,-0.012,0.015,-0.011,0.00061,0.002,-3.7e+02,-1.4e-05,-5.6e-05,-5.6e-06,2.1e-06,8.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0004,0.0004,9.6e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.6e-09,6.6e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.016,-0.00036,0.0024,-3.7e+02,-1.4e-05,-5.6e-05,-5.5e-06,3.7e-06,8.5e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00034,0.00034,9.6e-05,0.09,0.09,0.033,0.051,0.051,0.061,5.9e-09,5.9e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +12090000,0.7,0.0022,-0.014,0.71,-0.015,0.017,-0.022,-0.0018,0.0039,-3.7e+02,-1.4e-05,-5.6e-05,-5e-06,3.9e-06,8.4e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00035,0.00035,9.6e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.9e-09,5.9e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +12190000,0.7,0.0019,-0.014,0.71,-0.0086,0.013,-0.017,0.0014,0.002,-3.7e+02,-1.3e-05,-5.7e-05,-4.8e-06,6.7e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0003,0.0003,9.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.4e-09,5.4e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +12290000,0.7,0.0018,-0.014,0.71,-0.011,0.015,-0.016,0.00041,0.0034,-3.7e+02,-1.3e-05,-5.7e-05,-4.6e-06,6.4e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00031,0.00031,9.6e-05,0.1,0.1,0.028,0.059,0.059,0.059,5.4e-09,5.4e-09,2.7e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 +12390000,0.7,0.0015,-0.014,0.71,-0.0057,0.012,-0.015,0.003,0.0017,-3.7e+02,-1.3e-05,-5.8e-05,-4.9e-06,8.3e-06,1.7e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00027,0.00027,9.5e-05,0.079,0.079,0.026,0.05,0.05,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0 +12490000,0.7,0.0015,-0.014,0.71,-0.007,0.014,-0.018,0.0023,0.003,-3.7e+02,-1.3e-05,-5.7e-05,-5.4e-06,8.2e-06,1.7e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00028,0.00028,9.5e-05,0.092,0.092,0.026,0.059,0.059,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0 +12590000,0.7,0.0016,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0015,-3.7e+02,-1.4e-05,-5.8e-05,-5.3e-06,9.7e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00025,0.00025,9.5e-05,0.073,0.073,0.025,0.05,0.05,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0 +12690000,0.7,0.0016,-0.014,0.71,-0.015,0.013,-0.027,-0.0043,0.0027,-3.7e+02,-1.4e-05,-5.8e-05,-5.5e-06,9.9e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00026,0.00026,9.5e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0 +12790000,0.7,0.0017,-0.013,0.71,-0.02,0.0095,-0.03,-0.0076,0.0014,-3.7e+02,-1.4e-05,-5.8e-05,-5.3e-06,1e-05,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.7e-07,0,0,0,0,0,0,0,0 +12890000,0.7,0.0016,-0.013,0.71,-0.021,0.0095,-0.029,-0.0097,0.0023,-3.7e+02,-1.4e-05,-5.8e-05,-5.1e-06,9.8e-06,1.4e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00024,0.00024,9.5e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0 +12990000,0.7,0.0013,-0.014,0.71,-0.0088,0.0069,-0.03,-0.0011,0.0012,-3.7e+02,-1.3e-05,-5.9e-05,-4.5e-06,9.7e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.5e-05,0.064,0.064,0.025,0.049,0.049,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0 +13090000,0.7,0.0013,-0.014,0.71,-0.0095,0.0072,-0.03,-0.002,0.0019,-3.7e+02,-1.3e-05,-5.9e-05,-5e-06,9.4e-06,1.7e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.073,0.073,0.025,0.057,0.057,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0 +13190000,0.7,0.001,-0.014,0.71,-0.00039,0.0065,-0.027,0.0044,0.0012,-3.7e+02,-1.2e-05,-5.9e-05,-4.9e-06,8e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0 +13290000,0.7,0.001,-0.014,0.71,-0.00069,0.0073,-0.024,0.0043,0.0019,-3.7e+02,-1.2e-05,-5.9e-05,-4.3e-06,6.7e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.4e-05,0.068,0.069,0.027,0.057,0.057,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0 +13390000,0.7,0.00087,-0.014,0.71,0.0002,0.0063,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-3.8e-06,5e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.8e-07,0,0,0,0,0,0,0,0 +13490000,0.7,0.0009,-0.014,0.71,-0.00033,0.0062,-0.019,0.0033,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-3.3e-06,4.2e-06,1.9e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00021,9.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.7e-07,0,0,0,0,0,0,0,0 +13590000,0.7,0.00084,-0.014,0.71,-1.4e-05,0.0064,-0.021,0.0024,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-3.6e-06,3.9e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0 +13690000,0.7,0.00081,-0.014,0.71,0.00063,0.0082,-0.025,0.0024,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-2.9e-06,4.2e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.061,0.061,0.029,0.056,0.056,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0 +13790000,0.7,0.00069,-0.014,0.71,0.0013,0.0039,-0.027,0.0035,-0.00059,-3.7e+02,-1.2e-05,-6e-05,-2.9e-06,2e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.3e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0 +13890000,0.7,0.00066,-0.014,0.71,0.0017,0.0039,-0.031,0.0036,-0.00022,-3.7e+02,-1.2e-05,-6e-05,-2.5e-06,2.3e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.3e-05,0.058,0.058,0.03,0.056,0.056,0.05,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0 +13990000,0.7,0.00059,-0.014,0.71,0.0021,0.0013,-0.03,0.0045,-0.002,-3.7e+02,-1.1e-05,-6e-05,-2.3e-06,-3.7e-07,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.049,0.049,0.03,0.048,0.048,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0 +14090000,0.7,0.00057,-0.014,0.71,0.0021,0.0015,-0.031,0.0046,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-1.6e-06,-2.6e-07,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.055,0.055,0.031,0.056,0.056,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.3e-07,0,0,0,0,0,0,0,0 +14190000,0.7,0.00047,-0.014,0.71,0.0055,0.00089,-0.033,0.0068,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.3e-06,-1.4e-07,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.047,0.047,0.031,0.048,0.048,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0 +14290000,0.7,0.00047,-0.014,0.71,0.0063,0.0017,-0.032,0.0074,-0.0015,-3.7e+02,-1.1e-05,-6e-05,-9.7e-07,-7.9e-07,1.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.053,0.053,0.032,0.055,0.055,0.051,3.1e-09,3.1e-09,1.7e-09,3.6e-06,3.6e-06,6.7e-07,0,0,0,0,0,0,0,0 +14390000,0.7,0.00039,-0.014,0.71,0.0081,0.0025,-0.034,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-2.9e-07,-9.1e-07,1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,1.7e-09,3.6e-06,3.6e-06,6.3e-07,0,0,0,0,0,0,0,0 +14490000,0.7,0.00037,-0.013,0.71,0.0081,0.0038,-0.037,0.0095,-0.00098,-3.7e+02,-1.1e-05,-6e-05,-5.4e-08,-3.7e-07,9.7e-06,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.051,0.051,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,1.6e-09,3.6e-06,3.6e-06,6.2e-07,0,0,0,0,0,0,0,0 +14590000,0.7,0.00036,-0.013,0.71,0.0046,0.0021,-0.037,0.006,-0.0024,-3.7e+02,-1.1e-05,-6e-05,1.3e-08,-4.1e-06,1.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.2e-05,0.044,0.044,0.031,0.047,0.047,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0 +14690000,0.7,0.00032,-0.013,0.71,0.006,-0.00079,-0.034,0.0065,-0.0023,-3.7e+02,-1.1e-05,-6.1e-05,5e-07,-5.2e-06,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.6e-07,0,0,0,0,0,0,0,0 +14790000,0.7,0.00034,-0.013,0.71,0.0028,-0.0024,-0.03,0.0037,-0.0034,-3.7e+02,-1.2e-05,-6.1e-05,6.7e-07,-9.2e-06,2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.1e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0 +14890000,0.7,0.00033,-0.013,0.71,0.0042,-0.0014,-0.033,0.004,-0.0036,-3.7e+02,-1.2e-05,-6.1e-05,9.9e-07,-9e-06,1.9e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.1e-05,0.048,0.048,0.031,0.054,0.054,0.052,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.1e-07,0,0,0,0,0,0,0,0 +14990000,0.7,0.00033,-0.013,0.71,0.0031,-0.0016,-0.029,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,9.4e-07,-9.7e-06,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.042,0.042,0.03,0.047,0.047,0.051,2.4e-09,2.4e-09,1.5e-09,3.5e-06,3.5e-06,4.8e-07,0,0,0,0,0,0,0,0 +15090000,0.7,0.00025,-0.013,0.71,0.0035,-0.0018,-0.031,0.0034,-0.003,-3.7e+02,-1.2e-05,-6.1e-05,9.9e-07,-9.2e-06,2.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.4e-09,2.4e-09,1.4e-09,3.5e-06,3.5e-06,4.6e-07,0,0,0,0,0,0,0,0 +15190000,0.7,0.00027,-0.013,0.71,0.0029,-0.00058,-0.029,0.0027,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,9.6e-07,-9.4e-06,2.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.041,0.041,0.03,0.047,0.047,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.3e-07,0,0,0,0,0,0,0,0 +15290000,0.7,0.00023,-0.013,0.71,0.0034,-0.00041,-0.027,0.003,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.3e-06,-1e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9e-05,0.046,0.046,0.03,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.2e-07,0,0,0,0,0,0,0,0 +15390000,0.7,0.00023,-0.013,0.71,0.0027,-8.4e-05,-0.024,0.00049,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,1.9e-06,-1.1e-05,2.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.029,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.9e-07,0,0,0,0,0,0,0,0 +15490000,0.7,0.00025,-0.013,0.71,0.0039,-0.00045,-0.024,0.00083,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1e-05,2.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9e-05,0.045,0.045,0.029,0.053,0.053,0.053,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0 +15590000,0.7,0.00026,-0.013,0.71,0.0021,-0.00046,-0.023,-0.0014,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.1e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.3e-09,3.5e-06,3.5e-06,3.5e-07,0,0,0,0,0,0,0,0 +15690000,0.7,0.00027,-0.013,0.71,0.0024,-0.00062,-0.023,-0.0012,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.1e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00018,8.9e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0 +15790000,0.7,0.00022,-0.013,0.71,0.0029,-0.0023,-0.026,-0.001,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,8.9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3.1e-07,0,0,0,0,0,0,0,0 +15890000,0.7,0.00018,-0.013,0.71,0.0038,-0.0028,-0.024,-0.00068,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3e-07,0,0,0,0,0,0,0,0 +15990000,0.7,0.00012,-0.013,0.71,0.0037,-0.0037,-0.019,-0.00072,-0.0038,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.6e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.7e-09,1.7e-09,1.2e-09,3.4e-06,3.4e-06,2.8e-07,0,0,0,0,0,0,0,0 +16090000,0.7,0.00012,-0.013,0.71,0.0054,-0.0039,-0.016,-0.00029,-0.0042,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.7e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.8e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.7e-09,1.7e-09,1.1e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0 +16190000,0.7,0.00014,-0.013,0.71,0.0054,-0.0032,-0.014,-0.00047,-0.0034,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.6e-05,3.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.8e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.5e-07,0,0,0,0,0,0,0,0 +16290000,0.71,0.00016,-0.013,0.71,0.007,-0.004,-0.016,0.00015,-0.0038,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.6e-05,3.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0 +16390000,0.71,0.00015,-0.013,0.71,0.0059,-0.0042,-0.015,-0.00014,-0.003,-3.7e+02,-1.3e-05,-6.1e-05,3.2e-06,-1.5e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1.1e-09,3.3e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0 +16490000,0.71,0.00016,-0.013,0.71,0.0051,-0.0037,-0.018,0.00038,-0.0034,-3.7e+02,-1.3e-05,-6.1e-05,3.4e-06,-1.4e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.7e-05,0.042,0.042,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1e-09,3.3e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0 +16590000,0.71,0.00042,-0.013,0.71,0.0015,-0.001,-0.018,-0.0025,-2e-05,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-7.5e-06,4.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00016,0.00016,8.7e-05,0.037,0.037,0.022,0.046,0.046,0.051,1.3e-09,1.3e-09,1e-09,3.3e-06,3.3e-06,2e-07,0,0,0,0,0,0,0,0 +16690000,0.71,0.00041,-0.013,0.71,0.0017,-0.00053,-0.015,-0.0024,-9.7e-05,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-8.1e-06,4.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00016,8.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.3e-09,1.3e-09,9.9e-10,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0 +16790000,0.71,0.00056,-0.013,0.71,-0.0017,0.0017,-0.014,-0.0047,0.0026,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-2.5e-06,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.2e-09,1.2e-09,9.7e-10,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0 +16890000,0.71,0.00057,-0.013,0.71,-0.002,0.0025,-0.011,-0.0049,0.0028,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-2.9e-06,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.6e-05,0.041,0.041,0.021,0.052,0.052,0.051,1.2e-09,1.2e-09,9.5e-10,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0 +16990000,0.71,0.00051,-0.013,0.71,-0.0019,0.0005,-0.01,-0.0053,0.00091,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-7e-06,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.036,0.036,0.02,0.046,0.046,0.05,1.1e-09,1.1e-09,9.2e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0 +17090000,0.71,0.00048,-0.013,0.71,-0.0011,0.0015,-0.01,-0.0055,0.00099,-3.7e+02,-1.3e-05,-6e-05,3e-06,-6.9e-06,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.6e-05,0.04,0.04,0.02,0.052,0.052,0.05,1.1e-09,1.1e-09,9e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0 +17190000,0.71,0.00046,-0.013,0.71,-0.00066,0.0014,-0.011,-0.0057,-0.00048,-3.7e+02,-1.4e-05,-6e-05,3.2e-06,-1e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.6e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,8.9e-10,3.2e-06,3.2e-06,1.5e-07,0,0,0,0,0,0,0,0 +17290000,0.71,0.00044,-0.013,0.71,0.0014,0.0025,-0.0066,-0.0057,-0.0003,-3.7e+02,-1.4e-05,-6e-05,3e-06,-1.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.5e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,8.7e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0 +17390000,0.71,0.0004,-0.013,0.71,0.0021,0.0016,-0.0047,-0.0048,-0.0016,-3.7e+02,-1.4e-05,-6e-05,3.3e-06,-1.4e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00014,8.5e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,8.5e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0 +17490000,0.71,0.0004,-0.013,0.71,0.0026,0.0012,-0.0029,-0.0045,-0.0015,-3.7e+02,-1.4e-05,-6e-05,3.4e-06,-1.5e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0 +17590000,0.71,0.00031,-0.013,0.71,0.0039,2.9e-06,0.0026,-0.0038,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.5e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.9e-10,7.9e-10,8.1e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0 +17690000,0.71,0.00028,-0.013,0.71,0.0048,0.00072,0.002,-0.0034,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.6e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.9e-10,7.9e-10,7.9e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0 +17790000,0.71,0.00018,-0.013,0.71,0.0074,0.00043,0.00062,-0.0022,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.7e-05,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0 +17890000,0.71,0.00019,-0.013,0.71,0.0089,-0.00033,0.00072,-0.0014,-0.0021,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0 +17990000,0.71,0.00014,-0.013,0.71,0.011,-0.0021,0.0019,-0.00063,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,7.5e-10,3.1e-06,3.1e-06,1e-07,0,0,0,0,0,0,0,0 +18090000,0.71,0.00014,-0.013,0.71,0.011,-0.0022,0.0043,0.00048,-0.0021,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.7e-05,5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,7.3e-10,3.1e-06,3.1e-06,9.7e-08,0,0,0,0,0,0,0,0 +18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0012,0.0057,0.0014,-0.0016,-3.7e+02,-1.3e-05,-6.1e-05,4.3e-06,-1.6e-05,5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,7.2e-10,3.1e-06,3.1e-06,9.2e-08,0,0,0,0,0,0,0,0 +18290000,0.71,4.9e-05,-0.012,0.71,0.012,-0.0017,0.0068,0.0025,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.6e-05,5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,8.9e-08,0,0,0,0,0,0,0,0 +18390000,0.71,6.3e-05,-0.013,0.71,0.013,-9.4e-05,0.008,0.0031,-0.0013,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.6e-05,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.4e-08,0,0,0,0,0,0,0,0 +18490000,0.71,7.9e-05,-0.012,0.71,0.014,0.00032,0.0076,0.0045,-0.0013,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.6e-05,5.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.2e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8.2e-08,0,0,0,0,0,0,0,0 +18590000,0.71,8.2e-05,-0.012,0.71,0.013,0.00055,0.0058,0.0034,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.6e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.8e-08,0,0,0,0,0,0,0,0 +18690000,0.71,5.1e-05,-0.012,0.71,0.014,-0.00014,0.0039,0.0048,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.6e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00013,0.00012,8.2e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.5e-10,3.1e-06,3.1e-06,7.5e-08,0,0,0,0,0,0,0,0 +18790000,0.71,8e-05,-0.012,0.71,0.012,0.00016,0.0036,0.0037,-0.00087,-3.7e+02,-1.4e-05,-6.1e-05,4.7e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.2e-08,0,0,0,0,0,0,0,0 +18890000,0.71,0.0001,-0.012,0.71,0.013,0.00066,0.0042,0.0049,-0.00079,-3.7e+02,-1.4e-05,-6.1e-05,5.1e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,7e-08,0,0,0,0,0,0,0,0 +18990000,0.71,9e-05,-0.012,0.71,0.014,0.0016,0.0028,0.0062,-0.00066,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.6e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0 +19090000,0.71,7.5e-05,-0.012,0.71,0.014,0.0022,0.0059,0.0076,-0.00045,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.6e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.5e-08,0,0,0,0,0,0,0,0 +19190000,0.71,7.6e-05,-0.012,0.71,0.014,0.0021,0.0059,0.0085,-0.00041,-3.7e+02,-1.4e-05,-6.1e-05,5.4e-06,-1.6e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00011,8.1e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,5.9e-10,3e-06,3e-06,6.2e-08,0,0,0,0,0,0,0,0 +19290000,0.71,9.9e-05,-0.012,0.71,0.015,0.0014,0.0086,0.0099,-0.00022,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.6e-05,5.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00012,8e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,6e-08,0,0,0,0,0,0,0,0 +19390000,0.71,0.00011,-0.012,0.71,0.012,0.00047,0.012,0.0079,-0.00024,-3.7e+02,-1.4e-05,-6.1e-05,5.4e-06,-1.7e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.3e-10,3.3e-10,5.6e-10,3e-06,3e-06,5.8e-08,0,0,0,0,0,0,0,0 +19490000,0.71,0.00013,-0.012,0.71,0.011,-0.00024,0.0088,0.0091,-0.00023,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.7e-05,6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.6e-08,0,0,0,0,0,0,0,0 +19590000,0.71,0.00018,-0.012,0.71,0.0095,-0.0013,0.0081,0.0074,-0.00026,-3.7e+02,-1.4e-05,-6.1e-05,6e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,3e-06,3e-06,5.4e-08,0,0,0,0,0,0,0,0 +19690000,0.71,0.00018,-0.012,0.71,0.0099,-0.0035,0.0096,0.0083,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0 +19790000,0.71,0.00025,-0.012,0.71,0.0075,-0.0043,0.01,0.0067,-0.0004,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.7e-05,6.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19890000,0.71,0.0002,-0.012,0.71,0.0063,-0.0046,0.011,0.0074,-0.00086,-3.7e+02,-1.4e-05,-6.1e-05,6.2e-06,-1.7e-05,6.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19990000,0.71,0.00018,-0.012,0.71,0.0039,-0.0053,0.014,0.0061,-0.00072,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.6e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20090000,0.71,0.00018,-0.012,0.71,0.0036,-0.0072,0.014,0.0064,-0.0013,-3.7e+02,-1.4e-05,-6.1e-05,7.2e-06,-1.6e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20190000,0.71,0.00028,-0.012,0.71,0.0013,-0.0079,0.017,0.0041,-0.0011,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.5e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20290000,0.71,0.00024,-0.012,0.71,0.00017,-0.0095,0.015,0.0042,-0.0019,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.5e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.8e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20390000,0.71,0.00026,-0.012,0.71,-0.0023,-0.01,0.017,0.0023,-0.0015,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.3e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20490000,0.71,0.00031,-0.012,0.71,-0.0027,-0.011,0.016,0.0021,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.3e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.027,0.027,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,4.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20590000,0.71,0.00033,-0.012,0.71,-0.0024,-0.011,0.013,0.0018,-0.002,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.2e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0094,0.044,0.044,0.04,2e-10,2e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20690000,0.71,0.00036,-0.012,0.71,-0.0024,-0.012,0.015,0.0015,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.2e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20790000,0.71,0.00039,-0.012,0.71,-0.0035,-0.011,0.015,0.0013,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-9.8e-06,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.7e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20890000,0.71,0.00037,-0.012,0.71,-0.0039,-0.014,0.014,0.00092,-0.0037,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-9.9e-06,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,0.0001,0.0001,7.7e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +20990000,0.71,0.00038,-0.012,0.71,-0.0041,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-7.7e-06,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +21090000,0.71,0.00038,-0.012,0.71,-0.0043,-0.017,0.015,0.0022,-0.0046,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-7.8e-06,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.9e-05,9.9e-05,7.7e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +21190000,0.71,0.00041,-0.012,0.71,-0.0035,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-5.4e-06,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21290000,0.71,0.00045,-0.012,0.71,-0.0041,-0.018,0.016,0.0033,-0.0054,-3.7e+02,-1.4e-05,-6e-05,8e-06,-5.3e-06,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.6e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21390000,0.71,0.0005,-0.012,0.71,-0.0049,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-1.7e-06,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.6e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21490000,0.71,0.00051,-0.012,0.71,-0.0054,-0.018,0.015,0.0022,-0.0051,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-1.7e-06,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.7e-05,9.6e-05,7.6e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21590000,0.71,0.00053,-0.012,0.71,-0.0059,-0.015,0.015,0.0019,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,1.7e-06,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21690000,0.71,0.00054,-0.012,0.71,-0.0058,-0.016,0.017,0.0013,-0.0047,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,1.7e-06,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21790000,0.71,0.00056,-0.012,0.71,-0.0064,-0.011,0.015,9.8e-06,-0.00072,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,6.8e-06,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.4e-05,9.4e-05,7.5e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21890000,0.71,0.00056,-0.012,0.71,-0.0064,-0.012,0.016,-0.00063,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,6.8e-06,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.4e-05,7.5e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21990000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,1.1e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.3e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22090000,0.71,0.00062,-0.012,0.71,-0.0072,-0.0082,0.015,-0.0022,0.00066,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1.1e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.3e-05,7.5e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22190000,0.71,0.00059,-0.012,0.71,-0.007,-0.0073,0.015,-0.0019,0.00061,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1.2e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.2e-05,9.2e-05,7.5e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22290000,0.71,0.00063,-0.012,0.71,-0.0084,-0.008,0.015,-0.0026,-0.00016,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.2e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.2e-05,7.4e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22390000,0.71,0.00061,-0.012,0.71,-0.0089,-0.0075,0.017,-0.0022,-0.00015,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1.3e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.4e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22490000,0.71,0.00061,-0.012,0.71,-0.0096,-0.0074,0.018,-0.0032,-0.00092,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.3e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.2e-05,9.2e-05,7.4e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22590000,0.71,0.00059,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00016,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.4e-05,6.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22690000,0.71,0.00063,-0.012,0.71,-0.011,-0.0067,0.018,-0.0044,-0.00052,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1.4e-05,6.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9.1e-05,7.4e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22790000,0.71,0.00061,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00041,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.5e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22890000,0.71,0.00062,-0.012,0.71,-0.012,-0.0051,0.021,-0.0067,-0.00095,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.5e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00084,-3.7e+02,-1.4e-05,-5.9e-05,7.1e-06,1.5e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23090000,0.71,0.00057,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.5e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23190000,0.71,0.00064,-0.012,0.71,-0.015,-0.0065,0.024,-0.012,-0.0012,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.6e-05,6.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.6e-05,6.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.6e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.6e-05,7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.8e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23790000,0.71,0.005,0.00064,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.1e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.031,-0.0049,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.1e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.6e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-11,6.8e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.5e-05,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.1e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.5e-05,5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.6e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-11,6.5e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24390000,0.71,0.0038,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2.2e-05,4.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2.2e-05,4.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24590000,0.71,0.0052,0.0018,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2.1e-05,4.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.6e-06,2.1e-05,4.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2.5e-05,3.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.4e-05,8.4e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.5e-05,3.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,3.4e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.5e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.3e-05,7e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.1e-05,1.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.3e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.1e-05,1.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.3e-05,-2e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.3e-05,-1.8e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3e-05,-1.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3e-05,-1.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.8e-05,-3.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.2e-06,3.8e-05,-3.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8e-05,6.9e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.2e-06,3.4e-05,-5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,3.4e-05,-5.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.6e-05,-9.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.6e-05,-9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,6e-06,3.4e-05,-0.0001,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.9e-06,3.3e-05,-0.0001,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.6e-06,4.3e-05,-0.00014,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.7e-05,6.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.7e-06,4.3e-05,-0.00014,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.5e-06,2.1e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.8e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.5e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.5e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.4e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.5e-06,4e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.6e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.5e-06,3.9e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.2e-06,-5.9e-05,5.6e-06,6e-05,-0.00022,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.7e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.5e-06,5.9e-05,-0.00022,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.6e-06,5.8e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.5e-06,5.7e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.4e-06,5.8e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,5.7e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.4e-06,5.2e-05,-0.00017,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5.2e-06,5.1e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5.2e-06,4.7e-05,-0.00015,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,5e-06,4.6e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.9e-06,4.4e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.7e-05,6.5e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.1e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28590000,0.71,0.00083,0.00098,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,3.7e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28690000,0.71,0.00013,6.4e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.3e-05,-0.00011,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28790000,0.71,-0.00016,-0.00018,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.7e-06,1.8e-06,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28890000,0.71,-0.00018,3.5e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.7e-06,-2.5e-06,-0.00017,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +28990000,0.71,9.5e-06,0.00048,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.6e-06,-2.4e-05,-0.00025,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +29090000,0.71,0.00016,0.00089,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.5e-06,-2.9e-05,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +29190000,0.71,0.00038,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.5e-06,-4.8e-05,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +29290000,0.71,0.00074,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.4e-06,-5.4e-05,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4.2e-06,-7e-05,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.16,0.16,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.7e-05,4.2e-06,-7.4e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,4.1e-06,-9.7e-05,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.0091,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,4e-06,-0.00012,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.3e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.8e-06,-0.00013,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.7e-06,-0.00015,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00015,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00017,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00017,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30390000,0.71,0.003,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00018,-0.00024,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.5e-06,-0.00019,-0.00023,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.5e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.0002,-0.00021,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.00021,-0.00021,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.00021,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +30990000,0.71,0.0024,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00022,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00023,-0.00017,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,3.1e-06,-0.00024,-0.00015,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31290000,0.71,0.0019,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,3.1e-06,-0.00025,-0.00013,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31390000,0.71,0.0018,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00025,-0.00012,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00026,-0.0001,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00027,-8.6e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00027,-7.4e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00028,-5.6e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31890000,0.71,0.00086,0.00037,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00029,-4.3e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +31990000,0.71,0.00073,-8.8e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.0003,-2.4e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +32090000,0.71,0.00044,-0.00081,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-8.7e-06,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 +32190000,0.71,0.00023,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.00031,1.2e-05,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32290000,0.71,-1.7e-06,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,2.8e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32390000,0.71,-0.00018,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.00032,3.7e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32490000,0.71,-0.0003,-0.0032,0.71,-1.4,-0.82,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.00033,4.8e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32590000,0.71,-0.0003,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00033,5.6e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32690000,0.71,-0.00034,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00033,6.1e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,5.9e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32790000,0.71,-0.00031,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00034,7.1e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32890000,0.71,-0.00021,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,8.1e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +32990000,0.71,-8.4e-05,-0.0033,0.71,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,9.4e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33090000,0.71,-0.00012,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00035,0.0001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00035,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,8e-05,7.4e-05,6.1e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,7.9e-05,7.5e-05,6.5e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33490000,0.41,0.0068,0.00072,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5e-05,7.8e-05,7.7e-05,7e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33590000,0.25,0.00097,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,7.6e-05,7.8e-05,7.3e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.5e-05,8e-05,7.6e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.4e-05,7.2e-05,8e-05,7.6e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.8e-05,6.9e-05,7.8e-05,7.2e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.7e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.1e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.7e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +34290000,-0.61,-0.0023,-0.0085,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.7e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,6.5e-05,7.3e-05,6.5e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +34390000,-0.64,-0.0025,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00018,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00044,0.00018,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.048,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 +34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 +34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 +34790000,-0.67,-0.0021,-0.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00064,0.00037,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 +34890000,-0.68,-0.0021,-0.0016,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-06,-0.00064,0.00037,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 +34990000,-0.68,-0.0085,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.057,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35290000,-0.68,-0.0086,-0.0045,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.9e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 35390000,-0.68,-0.0086,-0.0045,0.73,0.5,0.4,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.079,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35490000,-0.68,-0.0087,-0.0045,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35590000,-0.68,-0.0056,-0.0045,0.73,0.41,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35690000,-0.68,-0.0056,-0.0044,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35790000,-0.68,-0.0034,-0.0044,0.73,0.35,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.0008,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35490000,-0.68,-0.0087,-0.0045,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35590000,-0.68,-0.0056,-0.0045,0.73,0.41,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35690000,-0.68,-0.0056,-0.0044,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00078,0.00051,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +35790000,-0.68,-0.0034,-0.0044,0.73,0.36,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.0008,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 35890000,-0.68,-0.0035,-0.0044,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.2e-06,-0.0008,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.066,0.068,0.0058,0.5,0.5,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -35990000,-0.68,-0.0016,-0.0043,0.73,0.3,0.29,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.4e-06,-0.00087,0.00059,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -36090000,-0.68,-0.0017,-0.0043,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00087,0.00059,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -36190000,-0.68,-0.0003,-0.0042,0.73,0.26,0.27,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00098,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36290000,-0.68,-0.00042,-0.0041,0.73,0.27,0.29,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00098,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36390000,-0.68,0.00061,-0.004,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.9e-06,-0.0011,0.00078,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 +35990000,-0.68,-0.0016,-0.0043,0.73,0.31,0.29,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.4e-06,-0.00087,0.00059,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +36090000,-0.68,-0.0017,-0.0043,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.6e-06,-0.00087,0.00059,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 +36190000,-0.68,-0.0003,-0.0042,0.73,0.26,0.27,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.6e-06,-0.00098,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 +36290000,-0.68,-0.00043,-0.0041,0.73,0.27,0.29,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00098,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 +36390000,-0.68,0.0006,-0.004,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 36490000,-0.68,0.00051,-0.004,0.73,0.24,0.26,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.2e-06,-0.0011,0.00078,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.059,0.061,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,6.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36590000,-0.68,0.0013,-0.0039,0.73,0.2,0.22,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00088,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.9e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36690000,-0.68,0.0013,-0.0038,0.74,0.2,0.24,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.4e-06,-0.0012,0.00088,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36790000,-0.68,0.0018,-0.0037,0.74,0.17,0.21,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0014,0.00097,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 +36590000,-0.68,0.0013,-0.0039,0.73,0.2,0.22,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00087,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.9e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 +36690000,-0.68,0.0013,-0.0038,0.74,0.2,0.24,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0012,0.00088,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 +36790000,-0.68,0.0018,-0.0037,0.74,0.17,0.21,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.6e-06,-0.0014,0.00097,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 36890000,-0.68,0.0017,-0.0037,0.74,0.17,0.22,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.7e-06,-0.0014,0.00097,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 -36990000,-0.68,0.0022,-0.0035,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.8e-06,-0.0015,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,5.9e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -37090000,-0.68,0.0021,-0.0035,0.74,0.15,0.19,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5e-06,-0.0015,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,2e-05,2.1e-05,5.9e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -37190000,-0.68,0.0025,-0.0034,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.2e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0 +36990000,-0.68,0.0022,-0.0036,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.9e-06,-0.0015,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,5.9e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 +37090000,-0.68,0.0021,-0.0035,0.74,0.15,0.19,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.1e-06,-0.0015,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,2e-05,2.1e-05,5.9e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 +37190000,-0.68,0.0025,-0.0034,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.3e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0 37290000,-0.68,0.0024,-0.0034,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.4e-06,-0.0016,0.0011,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.055,0.057,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0 -37390000,-0.68,0.0027,-0.0033,0.74,0.099,0.15,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 -37490000,-0.68,0.0026,-0.0032,0.74,0.099,0.15,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.6e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 +37390000,-0.68,0.0027,-0.0033,0.74,0.1,0.15,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.6e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 +37490000,-0.68,0.0026,-0.0032,0.74,0.099,0.15,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.7e-06,-0.0017,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 37590000,-0.68,0.0028,-0.0031,0.74,0.08,0.13,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0018,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.049,0.05,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 -37690000,-0.68,0.0027,-0.0032,0.74,0.078,0.13,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.9e-06,-0.0018,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 -37790000,-0.68,0.0028,-0.0031,0.74,0.062,0.11,-0.099,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.1e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.4e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0 +37690000,-0.68,0.0027,-0.0032,0.74,0.078,0.14,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6e-06,-0.0018,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 +37790000,-0.68,0.0028,-0.0031,0.74,0.063,0.11,-0.099,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.1e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.4e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0 37890000,-0.68,0.0028,-0.0031,0.74,0.06,0.12,-0.092,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.0019,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.3e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0 -37990000,-0.68,0.0029,-0.0031,0.74,0.046,0.1,-0.083,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.4e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.047,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 -38090000,-0.68,0.0028,-0.0031,0.74,0.042,0.1,-0.073,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 -38190000,-0.68,0.0029,-0.003,0.74,0.029,0.088,-0.065,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.7e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 -38290000,-0.68,0.0028,-0.003,0.74,0.026,0.089,-0.058,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.9e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 -38390000,-0.68,0.0029,-0.0029,0.74,0.018,0.077,-0.051,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 +37990000,-0.68,0.0029,-0.0031,0.74,0.046,0.1,-0.083,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.047,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 +38090000,-0.68,0.0028,-0.0031,0.74,0.043,0.1,-0.073,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 +38190000,-0.68,0.0029,-0.003,0.74,0.029,0.088,-0.065,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 +38290000,-0.68,0.0028,-0.003,0.74,0.027,0.089,-0.058,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.9e-06,-0.002,0.0014,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 +38390000,-0.68,0.0029,-0.0029,0.74,0.018,0.077,-0.051,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 38490000,-0.68,0.0028,-0.0029,0.74,0.015,0.078,-0.043,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.2e-06,-0.0021,0.0014,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 -38590000,-0.68,0.0028,-0.0028,0.74,0.01,0.067,-0.037,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.3e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38690000,-0.68,0.0028,-0.0028,0.74,0.0062,0.067,-0.03,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.8e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38790000,-0.68,0.0028,-0.0028,0.74,0.00071,0.055,-0.022,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.6e-06,-0.0022,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38890000,-0.68,0.0026,-0.0028,0.74,-0.0092,0.044,0.48,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.7e-06,-0.0022,0.0014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 +38590000,-0.68,0.0028,-0.0028,0.74,0.01,0.067,-0.037,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 +38690000,-0.68,0.0028,-0.0028,0.74,0.0063,0.067,-0.03,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.5e-06,-0.0021,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.8e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 +38790000,-0.68,0.0028,-0.0028,0.74,0.00084,0.055,-0.022,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.6e-06,-0.0022,0.0014,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 +38890000,-0.67,0.0026,-0.0028,0.74,-0.009,0.044,0.48,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.8e-06,-0.0022,0.0014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index eee7980a7d96..8205d93608af 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -63,92 +63,92 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6090000,0.98,-0.0068,-0.013,0.18,0.0051,0.016,-0.037,0.002,0.0047,0.0098,-1.9e-05,-5.5e-05,7.5e-07,-8.4e-10,9.3e-10,-0.0012,0.2,-6.1e-09,0.43,0,0,0,0,0,5.2e-06,0.00039,0.00039,0.00016,0.23,0.23,0.042,0.1,0.1,0.073,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4.4e-07,0,0,0,0,0,0,0,0 6190000,0.98,-0.0068,-0.013,0.18,0.0046,0.018,-0.035,0.0025,0.0065,0.01,-1.9e-05,-5.5e-05,7.5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,-6.1e-09,0.43,0,0,0,0,0,5.1e-06,0.00041,0.00041,0.00016,0.27,0.27,0.04,0.13,0.13,0.071,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4.1e-07,0,0,0,0,0,0,0,0 6290000,0.98,-0.0067,-0.013,0.18,0.0032,0.021,-0.039,0.003,0.0084,0.0039,-1.9e-05,-5.5e-05,7.5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,-6.1e-09,0.43,0,0,0,0,0,5e-06,0.00044,0.00044,0.00015,0.31,0.31,0.039,0.17,0.17,0.07,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,3.9e-07,0,0,0,0,0,0,0,0 -6390000,0.98,-0.0067,-0.013,0.19,0.004,0.018,-0.04,0.002,0.0067,0.0013,-1.8e-05,-5.6e-05,7.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.4e-05,0.00034,0.00034,0.0015,0.22,0.22,0.038,0.13,0.13,0.07,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0 -6490000,0.98,-0.0066,-0.013,0.19,0.0018,0.017,-0.037,0.0023,0.0084,0.0036,-1.8e-05,-5.6e-05,7.1e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.5e-05,0.00034,0.00034,0.00097,0.22,0.22,0.036,0.16,0.16,0.069,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3.4e-07,0,0,0,0,0,0,0,0 -6590000,0.98,-0.0066,-0.013,0.19,0.0012,0.019,-0.04,0.0025,0.01,0.00067,-1.8e-05,-5.6e-05,6.8e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-05,0.00034,0.00034,0.00071,0.23,0.23,0.035,0.19,0.19,0.068,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3.2e-07,0,0,0,0,0,0,0,0 -6690000,0.98,-0.0064,-0.013,0.19,-0.0014,0.022,-0.042,0.0025,0.012,-0.00016,-1.8e-05,-5.6e-05,6.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2e-05,0.00035,0.00035,0.00057,0.24,0.24,0.033,0.23,0.23,0.067,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3e-07,0,0,0,0,0,0,0,0 -6790000,0.98,-0.0065,-0.013,0.19,0.00046,0.024,-0.041,0.0024,0.014,-0.00097,-1.8e-05,-5.6e-05,5.9e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.7e-05,0.00035,0.00035,0.00048,0.26,0.26,0.032,0.28,0.28,0.067,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,2.8e-07,0,0,0,0,0,0,0,0 -6890000,0.98,-0.0063,-0.013,0.19,6.4e-05,0.024,-0.037,0.0024,0.017,0.0016,-1.8e-05,-5.6e-05,5.7e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00035,0.00035,0.00041,0.28,0.28,0.031,0.33,0.33,0.066,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0 -6990000,0.98,-0.0062,-0.013,0.19,8.3e-05,0.025,-0.036,0.0024,0.019,0.0018,-1.8e-05,-5.6e-05,5.6e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00036,0.00036,0.00036,0.3,0.3,0.03,0.39,0.39,0.065,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,2.5e-07,0,0,0,0,0,0,0,0 -7090000,0.98,-0.0061,-0.013,0.19,-0.00077,0.031,-0.036,0.0024,0.022,0.00072,-1.8e-05,-5.6e-05,5.6e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00036,0.00036,0.00032,0.33,0.33,0.029,0.45,0.45,0.065,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0 -7190000,0.98,-0.006,-0.013,0.19,-0.0011,0.033,-0.035,0.0022,0.025,-0.002,-1.8e-05,-5.6e-05,4.8e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.00037,0.00037,0.00029,0.35,0.35,0.028,0.52,0.52,0.064,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,2.2e-07,0,0,0,0,0,0,0,0 -7290000,0.98,-0.006,-0.013,0.19,-0.00028,0.038,-0.033,0.0021,0.029,0.0018,-1.8e-05,-5.6e-05,4.9e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,9.4e-06,0.00037,0.00037,0.00026,0.39,0.39,0.027,0.6,0.6,0.063,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0 -7390000,0.98,-0.0059,-0.013,0.19,-0.002,0.041,-0.031,0.002,0.033,0.004,-1.8e-05,-5.6e-05,5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00038,0.00038,0.00024,0.43,0.43,0.026,0.69,0.69,0.063,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0 -7490000,0.98,-0.0059,-0.013,0.19,0.00045,0.044,-0.025,0.002,0.037,0.01,-1.8e-05,-5.6e-05,6.2e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8.1e-06,0.00039,0.00039,0.00022,0.47,0.47,0.026,0.79,0.79,0.062,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0 -7590000,0.98,-0.0059,-0.013,0.19,0.0015,0.047,-0.022,0.0021,0.041,0.015,-1.8e-05,-5.6e-05,6.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0004,0.0004,0.00021,0.51,0.51,0.025,0.9,0.9,0.061,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0 -7690000,0.98,-0.0059,-0.013,0.19,0.0013,0.051,-0.022,0.0023,0.046,0.02,-1.8e-05,-5.6e-05,5.9e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,0.00041,0.00041,0.0002,0.56,0.56,0.024,1,1,0.061,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0 -7790000,0.98,-0.0058,-0.013,0.19,0.0029,0.054,-0.024,0.0024,0.051,0.015,-1.8e-05,-5.6e-05,5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,0.00041,0.00041,0.00018,0.61,0.61,0.023,1.2,1.2,0.06,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0 -7890000,0.98,-0.0058,-0.013,0.19,0.0017,0.058,-0.025,0.0026,0.056,0.011,-1.8e-05,-5.6e-05,4.4e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,0.00043,0.00043,0.00017,0.67,0.67,0.022,1.3,1.3,0.059,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0 -7990000,0.98,-0.0058,-0.013,0.19,0.002,0.061,-0.021,0.0027,0.061,0.014,-1.8e-05,-5.6e-05,4.5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00043,0.00043,0.00017,0.72,0.72,0.022,1.5,1.5,0.058,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0 -8090000,0.98,-0.0056,-0.013,0.19,0.0035,0.066,-0.022,0.003,0.068,0.012,-1.8e-05,-5.6e-05,1.8e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.8e-06,0.00045,0.00045,0.00016,0.79,0.79,0.021,1.7,1.7,0.058,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0 -8190000,0.98,-0.0057,-0.013,0.19,0.0042,0.071,-0.017,0.0033,0.073,0.018,-1.8e-05,-5.6e-05,-4.3e-08,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.6e-06,0.00045,0.00045,0.00015,0.85,0.85,0.02,1.9,1.9,0.057,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0 -8290000,0.98,-0.0057,-0.013,0.19,0.0065,0.076,-0.016,0.0038,0.081,0.018,-1.8e-05,-5.6e-05,-1.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.4e-06,0.00047,0.00047,0.00015,0.92,0.92,0.02,2.1,2.1,0.057,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0 -8390000,0.98,-0.0056,-0.013,0.19,0.0044,0.079,-0.015,0.0044,0.088,0.02,-1.8e-05,-5.6e-05,-2.1e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.2e-06,0.00048,0.00048,0.00014,1,1,0.019,2.4,2.4,0.057,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0 -8490000,0.98,-0.0055,-0.013,0.19,0.0042,0.082,-0.016,0.0047,0.094,0.015,-1.8e-05,-5.6e-05,-5.1e-08,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.1e-06,0.00049,0.00049,0.00014,1.1,1.1,0.019,2.6,2.6,0.056,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0 -8590000,0.98,-0.0055,-0.013,0.19,0.0054,0.086,-0.012,0.0052,0.1,0.02,-1.8e-05,-5.6e-05,-1.8e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.9e-06,0.0005,0.0005,0.00013,1.2,1.2,0.018,3,3,0.055,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0 -8690000,0.98,-0.0055,-0.013,0.19,0.0054,0.087,-0.014,0.0055,0.11,0.018,-1.8e-05,-5.6e-05,-1.5e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.8e-06,0.00051,0.0005,0.00013,1.2,1.2,0.018,3.2,3.2,0.055,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,9.9e-08,0,0,0,0,0,0,0,0 -8790000,0.98,-0.0055,-0.013,0.19,0.0069,0.091,-0.013,0.006,0.12,0.021,-1.8e-05,-5.6e-05,-3.9e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.7e-06,0.00052,0.00052,0.00013,1.3,1.3,0.017,3.6,3.6,0.054,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,9.4e-08,0,0,0,0,0,0,0,0 -8890000,0.98,-0.0056,-0.013,0.19,0.007,0.093,-0.009,0.0066,0.12,0.027,-1.7e-05,-5.6e-05,-2.1e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.6e-06,0.00052,0.00052,0.00012,1.4,1.4,0.017,3.9,3.9,0.053,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,9e-08,0,0,0,0,0,0,0,0 -8990000,0.98,-0.0055,-0.013,0.19,0.0062,0.099,-0.0082,0.0072,0.13,0.024,-1.7e-05,-5.6e-05,7.4e-08,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00054,0.00054,0.00012,1.5,1.5,0.016,4.4,4.4,0.053,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,8.6e-08,0,0,0,0,0,0,0,0 -9090000,0.98,-0.0055,-0.013,0.19,0.0065,0.1,-0.0092,0.0076,0.14,0.024,-1.7e-05,-5.6e-05,3.9e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00053,0.00053,0.00012,1.5,1.5,0.016,4.7,4.7,0.053,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,8.2e-08,0,0,0,0,0,0,0,0 -9190000,0.98,-0.0055,-0.013,0.19,0.01,0.1,-0.0087,0.0085,0.15,0.023,-1.7e-05,-5.6e-05,6.8e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00055,0.00055,0.00012,1.6,1.6,0.016,5.2,5.2,0.052,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,7.9e-08,0,0,0,0,0,0,0,0 -9290000,0.98,-0.0054,-0.013,0.19,0.012,0.1,-0.0071,0.0093,0.15,0.026,-1.7e-05,-5.6e-05,7.6e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00054,0.00054,0.00012,1.7,1.7,0.015,5.5,5.5,0.051,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,7.5e-08,0,0,0,0,0,0,0,0 -9390000,0.98,-0.0053,-0.013,0.19,0.013,0.11,-0.006,0.011,0.16,0.025,-1.7e-05,-5.6e-05,4.4e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00056,0.00056,0.00012,1.8,1.8,0.015,6.1,6.1,0.051,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,7.2e-08,0,0,0,0,0,0,0,0 -9490000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0043,0.011,0.16,0.028,-1.7e-05,-5.6e-05,5.6e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00055,0.00055,0.00011,1.8,1.8,0.014,6.4,6.4,0.051,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,6.9e-08,0,0,0,0,0,0,0,0 -9590000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0042,0.012,0.17,0.027,-1.7e-05,-5.6e-05,-8.8e-08,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00057,0.00057,0.00011,1.9,1.9,0.014,7,7,0.05,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0 +6390000,0.98,-0.0067,-0.013,0.19,0.0036,0.018,-0.04,0.002,0.0067,0.0013,-1.8e-05,-5.6e-05,7.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.4e-05,0.00034,0.00034,0.0015,0.22,0.22,0.038,0.13,0.13,0.07,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0 +6490000,0.98,-0.0066,-0.013,0.19,0.0015,0.017,-0.037,0.0023,0.0084,0.0036,-1.8e-05,-5.6e-05,7.1e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.5e-05,0.00034,0.00034,0.00097,0.22,0.22,0.036,0.16,0.16,0.069,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3.4e-07,0,0,0,0,0,0,0,0 +6590000,0.98,-0.0066,-0.013,0.19,0.00085,0.019,-0.04,0.0024,0.01,0.00067,-1.8e-05,-5.6e-05,6.8e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-05,0.00034,0.00034,0.00071,0.23,0.23,0.035,0.19,0.19,0.068,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3.2e-07,0,0,0,0,0,0,0,0 +6690000,0.98,-0.0064,-0.013,0.19,-0.0017,0.022,-0.042,0.0023,0.012,-0.00016,-1.8e-05,-5.6e-05,6.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2e-05,0.00035,0.00035,0.00057,0.24,0.24,0.033,0.23,0.23,0.067,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,3e-07,0,0,0,0,0,0,0,0 +6790000,0.98,-0.0065,-0.013,0.19,0.00011,0.024,-0.041,0.0022,0.014,-0.00097,-1.8e-05,-5.6e-05,5.9e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.7e-05,0.00035,0.00035,0.00048,0.26,0.26,0.032,0.28,0.28,0.067,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,2.8e-07,0,0,0,0,0,0,0,0 +6890000,0.98,-0.0063,-0.013,0.19,-0.00028,0.024,-0.037,0.0022,0.017,0.0016,-1.8e-05,-5.6e-05,5.7e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00035,0.00035,0.00041,0.28,0.28,0.031,0.33,0.33,0.066,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0 +6990000,0.98,-0.0062,-0.013,0.19,-0.00026,0.025,-0.036,0.0022,0.019,0.0018,-1.8e-05,-5.6e-05,5.6e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00036,0.00036,0.00036,0.3,0.3,0.03,0.39,0.39,0.065,1.5e-08,1.5e-08,4.8e-09,4e-06,4e-06,2.5e-07,0,0,0,0,0,0,0,0 +7090000,0.98,-0.0061,-0.013,0.19,-0.0011,0.031,-0.036,0.0021,0.022,0.00072,-1.8e-05,-5.6e-05,5.6e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00036,0.00036,0.00032,0.33,0.33,0.029,0.45,0.45,0.065,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0 +7190000,0.98,-0.006,-0.013,0.19,-0.0015,0.033,-0.035,0.0019,0.025,-0.002,-1.8e-05,-5.6e-05,4.8e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.00037,0.00037,0.00029,0.35,0.35,0.028,0.52,0.52,0.064,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,2.2e-07,0,0,0,0,0,0,0,0 +7290000,0.98,-0.006,-0.013,0.19,-0.00062,0.038,-0.033,0.0018,0.029,0.0018,-1.8e-05,-5.6e-05,4.9e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,9.4e-06,0.00037,0.00037,0.00026,0.39,0.39,0.027,0.6,0.6,0.063,1.5e-08,1.5e-08,4.7e-09,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0 +7390000,0.98,-0.0059,-0.013,0.19,-0.0023,0.041,-0.031,0.0016,0.033,0.004,-1.8e-05,-5.6e-05,5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00038,0.00038,0.00024,0.43,0.43,0.026,0.69,0.69,0.063,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0 +7490000,0.98,-0.0059,-0.013,0.19,0.00011,0.044,-0.025,0.0016,0.037,0.01,-1.8e-05,-5.6e-05,6.2e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,8.1e-06,0.00039,0.00039,0.00022,0.47,0.47,0.026,0.79,0.79,0.062,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0 +7590000,0.98,-0.0059,-0.013,0.19,0.0012,0.047,-0.022,0.0017,0.041,0.015,-1.8e-05,-5.6e-05,6.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.5e-06,0.0004,0.0004,0.00021,0.51,0.51,0.025,0.9,0.9,0.061,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0 +7690000,0.98,-0.0059,-0.013,0.19,0.00092,0.051,-0.022,0.0018,0.046,0.02,-1.8e-05,-5.6e-05,5.9e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,7.1e-06,0.00041,0.00041,0.0002,0.56,0.56,0.024,1,1,0.061,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0 +7790000,0.98,-0.0058,-0.013,0.19,0.0026,0.054,-0.024,0.0019,0.051,0.015,-1.8e-05,-5.6e-05,5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,0.00041,0.00041,0.00018,0.61,0.61,0.023,1.2,1.2,0.06,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0 +7890000,0.98,-0.0058,-0.013,0.19,0.0013,0.058,-0.025,0.002,0.056,0.011,-1.8e-05,-5.6e-05,4.4e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,0.00043,0.00043,0.00017,0.67,0.67,0.022,1.3,1.3,0.059,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0 +7990000,0.98,-0.0058,-0.013,0.19,0.0017,0.061,-0.021,0.0022,0.061,0.014,-1.8e-05,-5.6e-05,4.5e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00043,0.00043,0.00017,0.72,0.72,0.022,1.5,1.5,0.058,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0 +8090000,0.98,-0.0056,-0.013,0.19,0.0032,0.066,-0.022,0.0024,0.068,0.012,-1.8e-05,-5.6e-05,1.8e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.8e-06,0.00045,0.00045,0.00016,0.79,0.79,0.021,1.7,1.7,0.058,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0 +8190000,0.98,-0.0057,-0.013,0.19,0.0039,0.071,-0.017,0.0027,0.073,0.018,-1.8e-05,-5.6e-05,-4.3e-08,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.6e-06,0.00045,0.00045,0.00015,0.85,0.85,0.02,1.9,1.9,0.057,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0 +8290000,0.98,-0.0057,-0.013,0.19,0.0062,0.076,-0.016,0.0032,0.081,0.018,-1.8e-05,-5.6e-05,-1.3e-07,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.4e-06,0.00047,0.00047,0.00015,0.92,0.92,0.02,2.1,2.1,0.057,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0 +8390000,0.98,-0.0056,-0.013,0.19,0.0041,0.079,-0.015,0.0037,0.088,0.02,-1.8e-05,-5.6e-05,-2.1e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.2e-06,0.00048,0.00048,0.00014,1,1,0.019,2.4,2.4,0.057,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0 +8490000,0.98,-0.0055,-0.013,0.19,0.0039,0.082,-0.016,0.004,0.094,0.015,-1.8e-05,-5.6e-05,-5.1e-08,-8.4e-10,9.3e-10,-0.0013,0.2,0.002,0.43,0,0,0,0,0,5.1e-06,0.00049,0.00049,0.00014,1.1,1.1,0.019,2.6,2.6,0.056,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0 +8590000,0.98,-0.0055,-0.013,0.19,0.0051,0.086,-0.012,0.0045,0.1,0.02,-1.8e-05,-5.6e-05,-1.8e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.9e-06,0.0005,0.0005,0.00013,1.2,1.2,0.018,3,3,0.055,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0 +8690000,0.98,-0.0055,-0.013,0.19,0.0051,0.087,-0.014,0.0048,0.11,0.018,-1.8e-05,-5.6e-05,-1.5e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.8e-06,0.00051,0.0005,0.00013,1.2,1.2,0.018,3.2,3.2,0.055,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,9.9e-08,0,0,0,0,0,0,0,0 +8790000,0.98,-0.0055,-0.013,0.19,0.0066,0.091,-0.013,0.0053,0.12,0.021,-1.8e-05,-5.6e-05,-3.9e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.7e-06,0.00052,0.00052,0.00013,1.3,1.3,0.017,3.6,3.6,0.054,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,9.4e-08,0,0,0,0,0,0,0,0 +8890000,0.98,-0.0056,-0.013,0.19,0.0067,0.093,-0.009,0.0058,0.12,0.027,-1.7e-05,-5.6e-05,-2.1e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.6e-06,0.00052,0.00052,0.00012,1.4,1.4,0.017,3.9,3.9,0.053,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,9e-08,0,0,0,0,0,0,0,0 +8990000,0.98,-0.0055,-0.013,0.19,0.0059,0.099,-0.0082,0.0064,0.13,0.024,-1.7e-05,-5.6e-05,7.4e-08,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00054,0.00054,0.00012,1.5,1.5,0.016,4.4,4.4,0.053,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,8.6e-08,0,0,0,0,0,0,0,0 +9090000,0.98,-0.0055,-0.013,0.19,0.0062,0.1,-0.0092,0.0068,0.14,0.024,-1.7e-05,-5.6e-05,3.9e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00053,0.00053,0.00012,1.5,1.5,0.016,4.7,4.7,0.053,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,8.2e-08,0,0,0,0,0,0,0,0 +9190000,0.98,-0.0055,-0.013,0.19,0.01,0.1,-0.0087,0.0077,0.15,0.023,-1.7e-05,-5.6e-05,6.8e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00055,0.00055,0.00012,1.6,1.6,0.016,5.2,5.2,0.052,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,7.9e-08,0,0,0,0,0,0,0,0 +9290000,0.98,-0.0054,-0.013,0.19,0.012,0.1,-0.0071,0.0085,0.15,0.026,-1.7e-05,-5.6e-05,7.6e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00054,0.00054,0.00012,1.7,1.7,0.015,5.5,5.5,0.051,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,7.5e-08,0,0,0,0,0,0,0,0 +9390000,0.98,-0.0053,-0.013,0.19,0.012,0.11,-0.006,0.0097,0.16,0.025,-1.7e-05,-5.6e-05,4.4e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00056,0.00056,0.00012,1.8,1.8,0.015,6.1,6.1,0.051,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,7.2e-08,0,0,0,0,0,0,0,0 +9490000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0043,0.01,0.16,0.028,-1.7e-05,-5.6e-05,5.6e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00055,0.00055,0.00011,1.8,1.8,0.014,6.4,6.4,0.051,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,6.9e-08,0,0,0,0,0,0,0,0 +9590000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0042,0.011,0.17,0.027,-1.7e-05,-5.6e-05,-8.8e-08,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00057,0.00057,0.00011,1.9,1.9,0.014,7,7,0.05,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0 9690000,0.98,-0.0055,-0.013,0.19,0.012,0.11,-0.0013,0.012,0.17,0.028,-1.6e-05,-5.7e-05,-2.7e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00055,0.00055,0.00011,1.9,1.9,0.014,7.2,7.2,0.05,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,6.4e-08,0,0,0,0,0,0,0,0 -9790000,0.98,-0.0055,-0.013,0.19,0.013,0.11,-0.0027,0.014,0.18,0.027,-1.6e-05,-5.7e-05,-9.1e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00057,0.00057,0.00011,2.1,2.1,0.014,8,8,0.049,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0 -9890000,0.98,-0.0056,-0.013,0.19,0.015,0.11,-0.0014,0.014,0.18,0.027,-1.6e-05,-5.7e-05,-7.7e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00054,0.00054,0.00011,2,2,0.013,8.1,8.1,0.049,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,5.9e-08,0,0,0,0,0,0,0,0 +9790000,0.98,-0.0055,-0.013,0.19,0.013,0.11,-0.0027,0.013,0.18,0.027,-1.6e-05,-5.6e-05,-9.1e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00057,0.00057,0.00011,2.1,2.1,0.014,8,8,0.049,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0 +9890000,0.98,-0.0056,-0.013,0.19,0.015,0.11,-0.0014,0.013,0.18,0.027,-1.6e-05,-5.7e-05,-7.7e-07,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00054,0.00054,0.00011,2,2,0.013,8.1,8.1,0.049,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,5.9e-08,0,0,0,0,0,0,0,0 9990000,0.98,-0.0055,-0.013,0.19,0.017,0.11,-0.00068,0.015,0.19,0.025,-1.6e-05,-5.7e-05,-1.3e-06,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00056,0.00056,0.00011,2.2,2.2,0.013,8.9,8.9,0.049,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,5.7e-08,0,0,0,0,0,0,0,0 10090000,0.98,-0.0056,-0.013,0.19,0.015,0.1,0.00052,0.015,0.18,0.027,-1.6e-05,-5.7e-05,-1.9e-06,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00053,0.00053,0.00011,2.1,2.1,0.013,9,9,0.048,1.1e-08,1.1e-08,4e-09,4e-06,4e-06,5.5e-08,0,0,0,0,0,0,0,0 -10190000,0.98,-0.0056,-0.013,0.19,0.013,0.1,0.0014,0.017,0.19,0.025,-1.6e-05,-5.7e-05,-2.6e-06,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00055,0.00055,0.00011,2.2,2.2,0.012,9.8,9.8,0.048,1.1e-08,1.1e-08,3.9e-09,4e-06,4e-06,5.3e-08,0,0,0,0,0,0,0,0 +10190000,0.98,-0.0056,-0.013,0.19,0.013,0.1,0.0014,0.016,0.19,0.025,-1.6e-05,-5.7e-05,-2.6e-06,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00055,0.00055,0.00011,2.2,2.2,0.012,9.8,9.8,0.048,1.1e-08,1.1e-08,3.9e-09,4e-06,4e-06,5.3e-08,0,0,0,0,0,0,0,0 10290000,0.98,-0.0057,-0.013,0.19,0.013,0.097,0.00031,0.016,0.18,0.026,-1.5e-05,-5.7e-05,-2.3e-06,-8.4e-10,9.3e-10,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00052,0.00052,0.00011,2.1,2.1,0.012,9.7,9.7,0.048,1.1e-08,1.1e-08,3.9e-09,4e-06,4e-06,5.1e-08,0,0,0,0,0,0,0,0 10390000,0.98,-0.0057,-0.012,0.19,0.007,0.0047,-0.0025,0.00076,0.00013,0.027,-1.5e-05,-5.7e-05,-2.1e-06,-1.2e-09,1.2e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00054,0.00054,0.00011,0.25,0.25,0.56,0.25,0.25,0.048,1.1e-08,1.1e-08,3.8e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10490000,0.98,-0.0056,-0.012,0.19,0.0084,0.0066,0.007,0.0015,0.00065,0.032,-1.5e-05,-5.7e-05,-2.6e-06,-1.3e-08,9.5e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00055,0.00055,0.00011,0.26,0.26,0.55,0.26,0.26,0.057,1.1e-08,1.1e-08,3.8e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10590000,0.98,-0.0056,-0.012,0.19,-0.0012,0.0044,0.013,-0.0012,-0.0055,0.035,-1.5e-05,-5.7e-05,-2.2e-06,3.2e-06,-7.6e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00056,0.00056,0.00011,0.13,0.13,0.27,0.13,0.13,0.055,1.1e-08,1.1e-08,3.7e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10690000,0.98,-0.0055,-0.012,0.19,-9.4e-05,0.0051,0.016,-0.0012,-0.005,0.038,-1.5e-05,-5.7e-05,-2.3e-06,3.1e-06,-6.9e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00058,0.00058,0.00011,0.15,0.15,0.26,0.14,0.14,0.065,1.1e-08,1.1e-08,3.7e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 +10490000,0.98,-0.0056,-0.012,0.19,0.0085,0.0066,0.007,0.0015,0.00065,0.032,-1.5e-05,-5.7e-05,-2.6e-06,-1.3e-08,9.5e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00055,0.00055,0.00011,0.26,0.26,0.55,0.26,0.26,0.057,1.1e-08,1.1e-08,3.8e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 +10590000,0.98,-0.0056,-0.012,0.19,-0.0012,0.0044,0.013,-0.0012,-0.0055,0.035,-1.5e-05,-5.7e-05,-2.2e-06,3.2e-06,-7.8e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00056,0.00056,0.00011,0.13,0.13,0.27,0.13,0.13,0.055,1.1e-08,1.1e-08,3.7e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 +10690000,0.98,-0.0055,-0.012,0.19,-6.4e-05,0.0051,0.016,-0.0012,-0.005,0.038,-1.5e-05,-5.7e-05,-2.3e-06,3.2e-06,-7e-08,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00058,0.00058,0.00011,0.15,0.15,0.26,0.14,0.14,0.065,1.1e-08,1.1e-08,3.7e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 10790000,0.98,-0.0056,-0.012,0.19,0.0017,0.0016,0.014,-0.00078,-0.0047,0.04,-1.5e-05,-5.7e-05,-2.3e-06,5e-06,4.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00057,0.00057,0.00011,0.1,0.1,0.17,0.091,0.091,0.062,1e-08,1e-08,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10890000,0.98,-0.0056,-0.013,0.19,0.0018,0.0046,0.01,-0.00059,-0.0045,0.037,-1.5e-05,-5.7e-05,-1.6e-06,5e-06,4.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00059,0.00059,0.00011,0.12,0.12,0.16,0.098,0.098,0.068,1e-08,1e-08,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10990000,0.98,-0.0056,-0.013,0.19,0.0013,0.011,0.016,-0.00045,-0.0031,0.044,-1.5e-05,-5.8e-05,-1.8e-06,6.2e-06,5.9e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00055,0.00055,0.00011,0.094,0.094,0.12,0.073,0.073,0.065,9.9e-09,9.9e-09,3.5e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0 -11090000,0.98,-0.0058,-0.013,0.19,0.0023,0.015,0.02,-0.00031,-0.0019,0.048,-1.5e-05,-5.8e-05,-2.4e-06,6.2e-06,5.9e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00057,0.00057,0.00011,0.11,0.11,0.11,0.08,0.08,0.069,9.9e-09,9.9e-09,3.4e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0 +10890000,0.98,-0.0056,-0.013,0.19,0.0019,0.0046,0.01,-0.00059,-0.0045,0.037,-1.5e-05,-5.7e-05,-1.6e-06,5e-06,4.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00059,0.00059,0.00011,0.12,0.12,0.16,0.098,0.098,0.068,1e-08,1e-08,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 +10990000,0.98,-0.0056,-0.013,0.19,0.0014,0.011,0.016,-0.00045,-0.0031,0.044,-1.5e-05,-5.8e-05,-1.8e-06,6.2e-06,5.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00055,0.00055,0.00011,0.094,0.094,0.12,0.073,0.073,0.065,9.9e-09,9.9e-09,3.5e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0 +11090000,0.98,-0.0058,-0.013,0.19,0.0023,0.015,0.02,-0.0003,-0.0019,0.048,-1.5e-05,-5.8e-05,-2.4e-06,6.2e-06,5.9e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00057,0.00057,0.00011,0.11,0.11,0.11,0.08,0.08,0.069,9.9e-09,9.9e-09,3.4e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0 11190000,0.98,-0.006,-0.013,0.19,0.004,0.015,0.026,0.0011,-0.0019,0.055,-1.4e-05,-5.7e-05,-2.7e-06,5.7e-06,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00051,0.00051,0.00011,0.093,0.093,0.083,0.063,0.063,0.066,9.3e-09,9.3e-09,3.4e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0 -11290000,0.98,-0.006,-0.013,0.19,0.0041,0.016,0.026,0.0014,-0.00034,0.055,-1.4e-05,-5.7e-05,-2.9e-06,5.7e-06,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00053,0.00053,0.00011,0.12,0.12,0.077,0.07,0.07,0.069,9.3e-09,9.3e-09,3.3e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0 -11390000,0.98,-0.0061,-0.013,0.19,0.0025,0.014,0.016,0.00088,-0.001,0.047,-1.4e-05,-5.8e-05,-2.8e-06,1.1e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00046,0.00046,0.00011,0.094,0.094,0.062,0.057,0.057,0.066,8.5e-09,8.5e-09,3.2e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11490000,0.98,-0.0061,-0.013,0.19,0.0016,0.015,0.02,0.001,0.00043,0.053,-1.4e-05,-5.8e-05,-2.6e-06,1e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00048,0.00048,0.00011,0.12,0.12,0.057,0.065,0.065,0.067,8.5e-09,8.5e-09,3.2e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 +11290000,0.98,-0.006,-0.013,0.19,0.0042,0.016,0.026,0.0014,-0.00034,0.055,-1.4e-05,-5.7e-05,-2.9e-06,5.8e-06,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00053,0.00053,0.00011,0.12,0.12,0.077,0.07,0.07,0.069,9.3e-09,9.3e-09,3.3e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0 +11390000,0.98,-0.0061,-0.013,0.19,0.0025,0.014,0.016,0.00089,-0.001,0.047,-1.4e-05,-5.8e-05,-2.8e-06,1.1e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00046,0.00046,0.00011,0.094,0.094,0.062,0.057,0.057,0.066,8.5e-09,8.5e-09,3.2e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 +11490000,0.98,-0.0061,-0.013,0.19,0.0016,0.015,0.02,0.001,0.00043,0.053,-1.4e-05,-5.8e-05,-2.6e-06,1.1e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00048,0.00048,0.00011,0.12,0.12,0.057,0.065,0.065,0.067,8.5e-09,8.5e-09,3.2e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 11590000,0.98,-0.0064,-0.012,0.19,0.0034,0.012,0.018,0.00084,-0.00046,0.052,-1.3e-05,-5.8e-05,-2.6e-06,1.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00041,0.00041,0.00011,0.094,0.094,0.048,0.054,0.054,0.065,7.7e-09,7.7e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11690000,0.98,-0.0063,-0.012,0.19,0.0038,0.015,0.018,0.0012,0.00085,0.05,-1.3e-05,-5.8e-05,-2.3e-06,1.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00042,0.00042,0.00011,0.11,0.11,0.044,0.062,0.062,0.066,7.7e-09,7.7e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11790000,0.98,-0.0067,-0.012,0.19,0.0025,0.0096,0.019,0.0007,-0.0018,0.053,-1.2e-05,-5.9e-05,-1.6e-06,1.9e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00036,0.00036,0.00011,0.091,0.091,0.037,0.052,0.052,0.063,7.1e-09,7.1e-09,3e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 +11690000,0.98,-0.0063,-0.012,0.19,0.0039,0.015,0.018,0.0012,0.00085,0.05,-1.3e-05,-5.8e-05,-2.3e-06,1.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00042,0.00042,0.00011,0.11,0.11,0.044,0.062,0.062,0.066,7.7e-09,7.7e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 +11790000,0.98,-0.0067,-0.012,0.19,0.0025,0.0096,0.019,0.00071,-0.0018,0.053,-1.2e-05,-5.9e-05,-1.6e-06,1.9e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00036,0.00036,0.00011,0.091,0.091,0.037,0.052,0.052,0.063,7.1e-09,7.1e-09,3e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 11890000,0.98,-0.0068,-0.012,0.19,0.0052,0.011,0.017,0.001,-0.00086,0.054,-1.2e-05,-5.9e-05,-1.7e-06,1.9e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00037,0.00037,0.00011,0.11,0.11,0.034,0.061,0.061,0.063,7.1e-09,7.1e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -11990000,0.98,-0.0069,-0.012,0.19,0.0081,0.011,0.015,0.0021,-0.0019,0.05,-1.2e-05,-5.9e-05,-1.4e-06,1.9e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00032,0.00032,0.00011,0.087,0.087,0.03,0.051,0.051,0.061,6.5e-09,6.5e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12090000,0.98,-0.0069,-0.012,0.19,0.0097,0.011,0.018,0.003,-0.00077,0.056,-1.2e-05,-5.9e-05,-1.3e-06,1.9e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00033,0.00033,0.00011,0.1,0.1,0.027,0.06,0.06,0.06,6.5e-09,6.5e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 +11990000,0.98,-0.0069,-0.012,0.19,0.0082,0.011,0.015,0.0021,-0.0019,0.05,-1.2e-05,-5.9e-05,-1.4e-06,1.9e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00032,0.00032,0.00011,0.087,0.087,0.03,0.051,0.051,0.061,6.5e-09,6.5e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 +12090000,0.98,-0.0069,-0.012,0.19,0.0098,0.011,0.018,0.003,-0.00077,0.056,-1.2e-05,-5.9e-05,-1.3e-06,1.9e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00033,0.00033,0.00011,0.1,0.1,0.027,0.06,0.06,0.06,6.5e-09,6.5e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 12190000,0.98,-0.0067,-0.012,0.19,0.0078,0.01,0.017,0.0018,0.00035,0.058,-1.2e-05,-5.9e-05,-1.5e-06,2.1e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00028,0.00028,0.00011,0.082,0.082,0.024,0.05,0.05,0.058,6e-09,6e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12290000,0.98,-0.0068,-0.012,0.19,0.0055,0.0097,0.016,0.0025,0.0014,0.059,-1.2e-05,-5.9e-05,-1.7e-06,2.1e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00029,0.00029,0.00011,0.097,0.097,0.022,0.059,0.059,0.058,6e-09,6e-09,2.7e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 +12290000,0.98,-0.0068,-0.012,0.19,0.0056,0.0097,0.016,0.0025,0.0014,0.059,-1.2e-05,-5.9e-05,-1.7e-06,2.1e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00029,0.00029,0.00011,0.097,0.097,0.022,0.059,0.059,0.058,6e-09,6e-09,2.7e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 12390000,0.98,-0.0069,-0.012,0.19,0.0041,0.0066,0.014,0.0017,0.00046,0.053,-1.2e-05,-5.9e-05,-1.7e-06,2.4e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00026,0.00026,0.00011,0.077,0.077,0.02,0.05,0.05,0.056,5.6e-09,5.6e-09,2.7e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12490000,0.98,-0.0069,-0.012,0.19,0.0041,0.0075,0.018,0.0021,0.0012,0.055,-1.2e-05,-5.9e-05,-1.7e-06,2.3e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00027,0.00027,0.00011,0.09,0.09,0.018,0.058,0.058,0.055,5.6e-09,5.6e-09,2.6e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 +12490000,0.98,-0.0069,-0.012,0.19,0.0042,0.0075,0.018,0.0021,0.0012,0.055,-1.2e-05,-5.9e-05,-1.7e-06,2.4e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00027,0.00027,0.00011,0.09,0.09,0.018,0.058,0.058,0.055,5.6e-09,5.6e-09,2.6e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 12590000,0.98,-0.0071,-0.012,0.19,0.0079,0.001,0.019,0.0033,-0.0014,0.057,-1.1e-05,-5.9e-05,-1.7e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00024,0.00024,0.00011,0.072,0.072,0.017,0.049,0.049,0.054,5.3e-09,5.3e-09,2.5e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 12690000,0.98,-0.0071,-0.012,0.19,0.0084,-0.0012,0.019,0.0041,-0.0014,0.059,-1.1e-05,-5.9e-05,-1.6e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00025,0.00025,0.00011,0.084,0.084,0.016,0.058,0.058,0.053,5.3e-09,5.3e-09,2.5e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 12790000,0.98,-0.0073,-0.012,0.19,0.01,-0.0045,0.021,0.0041,-0.0044,0.061,-1e-05,-5.9e-05,-6.7e-07,2.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00023,0.00023,0.00011,0.068,0.068,0.014,0.049,0.049,0.052,5e-09,5e-09,2.4e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.0054,0.022,0.0052,-0.0049,0.064,-1e-05,-5.9e-05,-7.9e-08,2.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00024,0.00024,0.00011,0.078,0.078,0.013,0.058,0.058,0.051,5e-09,5e-09,2.4e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12990000,0.98,-0.0073,-0.012,0.19,0.008,-0.0033,0.022,0.0036,-0.0036,0.065,-1.1e-05,-6e-05,4.7e-07,2.5e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00022,0.00022,0.00011,0.063,0.063,0.012,0.049,0.049,0.05,4.8e-09,4.8e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.0054,0.022,0.0052,-0.0049,0.064,-1e-05,-5.9e-05,-7.8e-08,2.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00024,0.00024,0.00011,0.078,0.078,0.013,0.058,0.058,0.051,5e-09,5e-09,2.4e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 +12990000,0.98,-0.0073,-0.012,0.19,0.0081,-0.0033,0.022,0.0036,-0.0036,0.065,-1.1e-05,-6e-05,4.7e-07,2.5e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00022,0.00022,0.00011,0.063,0.063,0.012,0.049,0.049,0.05,4.8e-09,4.8e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13090000,0.98,-0.0073,-0.012,0.19,0.009,-0.0032,0.02,0.0044,-0.0039,0.064,-1.1e-05,-6e-05,1.2e-06,2.6e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00023,0.00023,0.00011,0.073,0.073,0.012,0.057,0.057,0.049,4.8e-09,4.8e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13190000,0.98,-0.0073,-0.012,0.19,0.0039,-0.0048,0.019,0.00096,-0.0046,0.064,-1.1e-05,-6e-05,1.6e-06,2.7e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.00011,0.06,0.06,0.011,0.049,0.049,0.047,4.5e-09,4.5e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13290000,0.98,-0.0073,-0.012,0.19,0.0036,-0.0058,0.016,0.0013,-0.0051,0.064,-1.1e-05,-6e-05,1.7e-06,2.7e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00022,0.00022,0.00011,0.068,0.068,0.01,0.057,0.057,0.047,4.5e-09,4.5e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13390000,0.98,-0.0073,-0.012,0.19,0.0027,-0.0038,0.016,0.00085,-0.0038,0.064,-1.1e-05,-6e-05,1.5e-06,2.7e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.00011,0.057,0.057,0.0097,0.049,0.049,0.046,4.3e-09,4.3e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13490000,0.98,-0.0073,-0.012,0.19,0.0032,-0.0021,0.015,0.0012,-0.004,0.061,-1.1e-05,-6e-05,1.8e-06,2.8e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.0001,0.064,0.064,0.0093,0.057,0.057,0.045,4.3e-09,4.3e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13590000,0.98,-0.0073,-0.012,0.19,0.0077,-0.0023,0.017,0.004,-0.0032,0.059,-1.1e-05,-6e-05,1.7e-06,3e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.054,0.054,0.0089,0.048,0.048,0.044,4.1e-09,4.1e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13690000,0.98,-0.0072,-0.012,0.19,0.0077,-0.0037,0.017,0.0048,-0.0035,0.062,-1.1e-05,-6e-05,2.1e-06,3e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.0001,0.061,0.061,0.0086,0.056,0.056,0.044,4.1e-09,4.1e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13790000,0.98,-0.0071,-0.012,0.19,0.015,0.0005,0.017,0.0083,-0.00097,0.061,-1.1e-05,-5.9e-05,1.9e-06,3.4e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0082,0.048,0.048,0.043,3.9e-09,3.9e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +13690000,0.98,-0.0072,-0.012,0.19,0.0077,-0.0038,0.017,0.0048,-0.0035,0.062,-1.1e-05,-6e-05,2.1e-06,3e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.0001,0.061,0.061,0.0086,0.056,0.056,0.044,4.1e-09,4.1e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +13790000,0.98,-0.0071,-0.012,0.19,0.015,0.0005,0.017,0.0083,-0.00097,0.061,-1.1e-05,-5.9e-05,1.9e-06,3.4e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0082,0.048,0.048,0.043,3.9e-09,3.9e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13890000,0.98,-0.0071,-0.012,0.19,0.016,0.0012,0.018,0.0098,-0.00087,0.063,-1.1e-05,-5.9e-05,2.4e-06,3.4e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.0001,0.058,0.058,0.008,0.056,0.056,0.042,3.9e-09,3.9e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0013,0.017,0.0074,-0.0023,0.062,-1.1e-05,-6e-05,2.9e-06,3.2e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.049,0.049,0.0077,0.048,0.048,0.041,3.7e-09,3.7e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0031,0.018,0.0089,-0.0024,0.059,-1.1e-05,-6e-05,1.9e-06,3.3e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00021,0.00021,0.0001,0.056,0.056,0.0076,0.055,0.055,0.041,3.7e-09,3.7e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14190000,0.98,-0.0071,-0.011,0.19,0.01,-0.0018,0.018,0.008,-0.0018,0.059,-1.1e-05,-6e-05,1.5e-06,3.4e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.047,0.047,0.0074,0.048,0.048,0.04,3.5e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +14190000,0.98,-0.0071,-0.012,0.19,0.01,-0.0018,0.018,0.008,-0.0018,0.059,-1.1e-05,-6e-05,1.5e-06,3.4e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0002,0.0002,0.0001,0.047,0.047,0.0074,0.048,0.048,0.04,3.5e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0018,0.016,0.009,-0.002,0.063,-1.1e-05,-6e-05,1.6e-06,3.4e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.054,0.054,0.0073,0.055,0.055,0.04,3.5e-09,3.5e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0048,0.017,0.0084,-0.0031,0.068,-1.1e-05,-6e-05,1.9e-06,3.2e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.046,0.046,0.0071,0.048,0.048,0.039,3.3e-09,3.3e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0046,0.021,0.0095,-0.0036,0.07,-1.1e-05,-6e-05,1.4e-06,3.2e-05,3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.052,0.052,0.0071,0.055,0.055,0.038,3.3e-09,3.3e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0046,0.021,0.0095,-0.0036,0.07,-1.1e-05,-6e-05,1.4e-06,3.2e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.052,0.052,0.0071,0.055,0.055,0.038,3.3e-09,3.3e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14590000,0.98,-0.0073,-0.011,0.19,0.008,-0.0047,0.019,0.0059,-0.0042,0.066,-1.1e-05,-6e-05,1.3e-06,3e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.045,0.045,0.007,0.047,0.047,0.038,3.1e-09,3.1e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14690000,0.98,-0.0073,-0.011,0.19,0.0072,-0.0047,0.019,0.0066,-0.0047,0.066,-1.1e-05,-6e-05,1.6e-06,3e-05,2.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.05,0.05,0.007,0.055,0.055,0.037,3.1e-09,3.1e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14790000,0.98,-0.0072,-0.011,0.19,0.0089,0.0024,0.019,0.0053,0.00077,0.069,-1.2e-05,-6e-05,2.1e-06,3.1e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.044,0.044,0.0069,0.047,0.047,0.037,2.9e-09,2.9e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14890000,0.98,-0.0071,-0.011,0.19,0.0076,1.1e-05,0.023,0.0061,0.0009,0.07,-1.2e-05,-6e-05,2.6e-06,3.1e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.049,0.049,0.007,0.054,0.054,0.037,2.9e-09,2.9e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +14890000,0.98,-0.0071,-0.011,0.19,0.0076,1.1e-05,0.023,0.0061,0.0009,0.07,-1.2e-05,-6e-05,2.6e-06,3.2e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.049,0.049,0.007,0.054,0.054,0.037,2.9e-09,2.9e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 14990000,0.98,-0.0073,-0.011,0.19,0.0063,-0.0016,0.026,0.0047,-0.00071,0.072,-1.2e-05,-6e-05,2.8e-06,3e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.043,0.043,0.0069,0.047,0.047,0.036,2.7e-09,2.7e-09,1.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 15090000,0.98,-0.0072,-0.011,0.19,0.0063,-0.00056,0.03,0.0054,-0.00086,0.074,-1.2e-05,-6e-05,2.8e-06,3e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,9.9e-05,0.048,0.048,0.007,0.054,0.054,0.036,2.7e-09,2.7e-09,1.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 15190000,0.98,-0.0074,-0.011,0.19,0.0044,-0.0016,0.03,0.0042,-0.00077,0.076,-1.2e-05,-6.1e-05,2.7e-06,2.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.042,0.042,0.007,0.047,0.047,0.036,2.5e-09,2.5e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 @@ -158,14 +158,14 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 15590000,0.98,-0.0078,-0.011,0.19,0.0082,-0.0067,0.029,0.0063,-0.0047,0.073,-1.1e-05,-6.1e-05,3.3e-06,3.7e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.7e-05,0.041,0.041,0.0072,0.047,0.047,0.035,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 15690000,0.98,-0.0078,-0.011,0.19,0.01,-0.0098,0.029,0.0072,-0.0055,0.074,-1.1e-05,-6.1e-05,3.7e-06,3.8e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0073,0.053,0.053,0.034,2.1e-09,2.1e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 15790000,0.98,-0.0077,-0.011,0.19,0.0065,-0.0091,0.029,0.0055,-0.0043,0.075,-1.1e-05,-6.1e-05,4.2e-06,3.7e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.04,0.04,0.0073,0.046,0.046,0.034,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0075,0.03,0.0061,-0.0051,0.075,-1.1e-05,-6.1e-05,3.8e-06,3.9e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.045,0.045,0.0074,0.053,0.053,0.034,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 +15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0075,0.03,0.0061,-0.0051,0.075,-1.1e-05,-6.1e-05,3.8e-06,3.9e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.045,0.045,0.0074,0.053,0.053,0.034,2e-09,2e-09,1.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.006,0.027,0.0048,-0.0039,0.074,-1.2e-05,-6.1e-05,3.8e-06,4.1e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.5e-05,0.04,0.04,0.0075,0.046,0.046,0.034,1.8e-09,1.8e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 16090000,0.98,-0.0076,-0.011,0.19,0.0027,-0.0073,0.024,0.0051,-0.0046,0.074,-1.2e-05,-6.1e-05,3.6e-06,4.3e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.5e-05,0.045,0.045,0.0076,0.053,0.053,0.034,1.8e-09,1.8e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.0049,0.023,0.0027,-0.0034,0.071,-1.2e-05,-6.1e-05,3.3e-06,4.4e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 16290000,0.98,-0.0075,-0.011,0.19,-0.00095,-0.0064,0.023,0.0026,-0.004,0.072,-1.2e-05,-6.1e-05,3.4e-06,4.4e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.044,0.044,0.0077,0.053,0.053,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 16390000,0.98,-0.0075,-0.011,0.19,0.0015,-0.0057,0.023,0.0036,-0.003,0.072,-1.2e-05,-6.1e-05,3.7e-06,5e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00016,9.3e-05,0.038,0.039,0.0077,0.046,0.046,0.034,1.5e-09,1.5e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 16490000,0.98,-0.0076,-0.011,0.19,0.0035,-0.0073,0.026,0.0039,-0.0037,0.076,-1.2e-05,-6.1e-05,3.6e-06,4.9e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-09,1.5e-09,1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16590000,0.98,-0.0075,-0.011,0.19,0.0076,-0.0073,0.029,0.0034,-0.0029,0.076,-1.2e-05,-6.1e-05,3.6e-06,5e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.038,0.038,0.0079,0.046,0.046,0.034,1.4e-09,1.4e-09,1e-09,3.2e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 +16590000,0.98,-0.0075,-0.011,0.19,0.0076,-0.0073,0.029,0.0034,-0.0029,0.076,-1.2e-05,-6.1e-05,3.6e-06,5.1e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.038,0.038,0.0079,0.046,0.046,0.034,1.4e-09,1.4e-09,1e-09,3.2e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 16690000,0.98,-0.0076,-0.011,0.19,0.009,-0.012,0.029,0.0042,-0.0038,0.077,-1.2e-05,-6.1e-05,3.8e-06,5.2e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.043,0.043,0.008,0.053,0.053,0.034,1.4e-09,1.4e-09,9.9e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0027,0.077,-1.2e-05,-6.1e-05,3.9e-06,5.3e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.1e-05,0.037,0.037,0.0081,0.046,0.046,0.034,1.2e-09,1.2e-09,9.7e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 16890000,0.98,-0.0074,-0.011,0.19,0.0089,-0.011,0.029,0.0042,-0.0038,0.076,-1.2e-05,-6.1e-05,4.3e-06,5.5e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.1e-05,0.042,0.042,0.0082,0.053,0.053,0.034,1.2e-09,1.2e-09,9.5e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 @@ -176,21 +176,21 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 17390000,0.98,-0.0075,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0058,0.076,-1.3e-05,-6e-05,3.9e-06,7.2e-05,2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00014,0.00014,8.8e-05,0.035,0.035,0.0084,0.046,0.046,0.034,9.1e-10,9.1e-10,8.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 17490000,0.98,-0.0075,-0.011,0.19,0.0047,-0.019,0.029,0.0062,-0.0077,0.078,-1.3e-05,-6e-05,3.7e-06,7.3e-05,2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.8e-05,0.039,0.039,0.0085,0.052,0.052,0.034,9.1e-10,9.1e-10,8.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 17590000,0.98,-0.0074,-0.011,0.19,0.00085,-0.015,0.028,0.0024,-0.0057,0.075,-1.3e-05,-6.1e-05,3.7e-06,7.2e-05,2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.035,0.035,0.0085,0.046,0.046,0.034,8.2e-10,8.2e-10,8.1e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17690000,0.98,-0.0075,-0.011,0.19,-9.3e-05,-0.016,0.029,0.0025,-0.0073,0.078,-1.3e-05,-6.1e-05,3.7e-06,7.3e-05,2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.039,0.039,0.0086,0.052,0.052,0.034,8.2e-10,8.2e-10,7.9e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 +17690000,0.98,-0.0075,-0.011,0.19,-9.6e-05,-0.016,0.029,0.0025,-0.0073,0.078,-1.3e-05,-6.1e-05,3.7e-06,7.3e-05,2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.039,0.039,0.0086,0.052,0.052,0.034,8.2e-10,8.2e-10,7.9e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 17790000,0.98,-0.0074,-0.011,0.19,0.0026,-0.014,0.029,0.0035,-0.0061,0.083,-1.4e-05,-6e-05,3.8e-06,7.6e-05,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00013,8.7e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.4e-10,7.4e-10,7.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 17890000,0.98,-0.0073,-0.011,0.19,0.0047,-0.016,0.029,0.0039,-0.0076,0.087,-1.4e-05,-6e-05,3.8e-06,7.5e-05,3.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.6e-05,0.038,0.038,0.0086,0.052,0.052,0.035,7.4e-10,7.4e-10,7.6e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 17990000,0.98,-0.0071,-0.011,0.19,0.0041,-0.009,0.029,0.0031,-0.0018,0.088,-1.4e-05,-6e-05,3.8e-06,7.9e-05,4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.033,0.033,0.0086,0.046,0.046,0.034,6.7e-10,6.7e-10,7.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 18090000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0095,0.028,0.0035,-0.0028,0.086,-1.4e-05,-6e-05,3.7e-06,8.2e-05,3.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.037,0.037,0.0087,0.052,0.052,0.035,6.7e-10,6.7e-10,7.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0085,0.028,0.0041,-0.002,0.084,-1.4e-05,-6e-05,4.1e-06,8.7e-05,3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-10,6.1e-10,7.2e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -18290000,0.98,-0.0073,-0.011,0.19,0.0045,-0.009,0.027,0.0045,-0.0029,0.082,-1.4e-05,-6e-05,4.1e-06,9e-05,3.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.4e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6e-10,6.1e-10,7e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 +18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0085,0.028,0.0041,-0.002,0.084,-1.4e-05,-6e-05,4.1e-06,8.8e-05,3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-10,6.1e-10,7.2e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 +18290000,0.98,-0.0073,-0.011,0.19,0.0045,-0.009,0.027,0.0045,-0.0029,0.082,-1.4e-05,-6e-05,4.1e-06,9e-05,3.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.4e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6e-10,6.1e-10,7e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.0077,0.027,0.0061,-0.0022,0.082,-1.4e-05,-6e-05,4e-06,9.6e-05,3.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00012,0.00012,8.4e-05,0.032,0.032,0.0086,0.045,0.045,0.035,5.5e-10,5.5e-10,6.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 18490000,0.98,-0.0072,-0.011,0.19,0.0082,-0.0077,0.026,0.0069,-0.003,0.083,-1.4e-05,-6e-05,4.1e-06,9.6e-05,3.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.3e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.5e-10,5.5e-10,6.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18590000,0.98,-0.007,-0.011,0.19,0.0066,-0.007,0.026,0.0056,-0.0023,0.086,-1.5e-05,-6e-05,3.8e-06,9.5e-05,3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-10,4.9e-10,6.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +18590000,0.98,-0.007,-0.011,0.19,0.0066,-0.007,0.026,0.0055,-0.0023,0.086,-1.5e-05,-6e-05,3.8e-06,9.5e-05,3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-10,4.9e-10,6.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.006,0.024,0.0062,-0.0029,0.084,-1.5e-05,-6e-05,4e-06,9.7e-05,3.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-10,4.9e-10,6.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.0057,0.023,0.0062,-0.0023,0.082,-1.5e-05,-6e-05,4e-06,0.0001,3.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.5e-10,4.5e-10,6.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 18890000,0.98,-0.007,-0.011,0.19,0.0043,-0.0053,0.021,0.0067,-0.003,0.078,-1.5e-05,-6e-05,3.8e-06,0.0001,3.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.5e-10,4.5e-10,6.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 18990000,0.98,-0.0069,-0.011,0.19,0.0026,-0.0054,0.022,0.0055,-0.0024,0.082,-1.5e-05,-6e-05,3.7e-06,0.0001,3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00011,8.1e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4.1e-10,4.1e-10,6.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19090000,0.98,-0.007,-0.011,0.19,0.00063,-0.0059,0.023,0.0057,-0.0029,0.078,-1.5e-05,-6e-05,3.9e-06,0.00011,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4.1e-10,4.1e-10,6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19090000,0.98,-0.007,-0.011,0.19,0.00062,-0.0059,0.023,0.0057,-0.0029,0.078,-1.5e-05,-6e-05,3.9e-06,0.00011,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4.1e-10,4.1e-10,6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 19190000,0.98,-0.0069,-0.011,0.19,-0.00087,-0.0056,0.022,0.0048,-0.0024,0.077,-1.5e-05,-6e-05,3.5e-06,0.00011,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.029,0.029,0.0086,0.045,0.045,0.036,3.7e-10,3.7e-10,5.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0054,0.022,0.0047,-0.0029,0.076,-1.5e-05,-6e-05,3.4e-06,0.00011,2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.031,0.031,0.0087,0.051,0.051,0.036,3.7e-10,3.7e-10,5.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 19390000,0.98,-0.007,-0.011,0.19,-0.0022,-0.0019,0.024,0.004,-0.001,0.075,-1.5e-05,-6e-05,3.3e-06,0.00011,3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.4e-10,3.4e-10,5.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 @@ -201,34 +201,34 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.0017,0.022,0.0057,-0.0023,0.068,-1.5e-05,-6e-05,2.7e-06,0.00013,2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.00011,7.7e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0016,0.019,0.0061,-0.00076,0.065,-1.5e-05,-5.9e-05,2.7e-06,0.00013,1.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.6e-10,2.6e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0038,0.019,0.0055,-0.001,0.068,-1.5e-05,-5.9e-05,2.7e-06,0.00013,2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.0001,7.6e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.6e-10,2.6e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20190000,0.98,-0.0071,-0.011,0.19,-0.004,-0.0013,0.02,0.0065,-0.00076,0.068,-1.5e-05,-5.9e-05,2.4e-06,0.00013,1.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +20190000,0.98,-0.0071,-0.011,0.19,-0.004,-0.0013,0.02,0.0065,-0.00075,0.068,-1.5e-05,-5.9e-05,2.4e-06,0.00013,1.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20290000,0.98,-0.0071,-0.011,0.19,-0.0072,-0.0024,0.02,0.006,-0.00088,0.069,-1.5e-05,-5.9e-05,2.3e-06,0.00013,1.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20390000,0.98,-0.0071,-0.011,0.19,-0.0078,-0.0012,0.02,0.0069,-0.00063,0.07,-1.5e-05,-5.9e-05,2.4e-06,0.00013,1.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.5e-05,0.025,0.025,0.0084,0.044,0.044,0.036,2.2e-10,2.2e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20490000,0.98,-0.0071,-0.011,0.19,-0.012,-0.0021,0.02,0.0059,-0.00077,0.068,-1.5e-05,-5.9e-05,2.4e-06,0.00014,1.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.2e-10,2.2e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0031,0.02,0.0069,-0.00065,0.066,-1.5e-05,-5.9e-05,2.6e-06,0.00014,1.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +20590000,0.98,-0.007,-0.011,0.19,-0.012,-0.0031,0.02,0.0069,-0.00065,0.066,-1.5e-05,-5.9e-05,2.6e-06,0.00014,1.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20690000,0.98,-0.007,-0.011,0.19,-0.013,-0.0019,0.021,0.0057,-0.00085,0.066,-1.5e-05,-5.9e-05,2.4e-06,0.00014,1.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.9e-05,7.4e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20790000,0.98,-0.0064,-0.011,0.19,-0.016,0.00067,0.0055,0.0048,-0.00067,0.065,-1.5e-05,-5.9e-05,2.5e-06,0.00014,1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.7e-05,7.3e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20890000,0.98,0.0027,-0.0073,0.19,-0.022,0.013,-0.11,0.0029,4.2e-05,0.059,-1.5e-05,-5.9e-05,2.5e-06,0.00014,1.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.9e-05,9.8e-05,7.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.031,-0.25,0.0022,0.00066,0.044,-1.5e-05,-5.9e-05,2.4e-06,0.00014,1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.7e-05,9.5e-05,7.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.047,-0.37,-0.0017,0.0046,0.013,-1.5e-05,-5.9e-05,2.4e-06,0.00014,1.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.7e-05,9.6e-05,7.2e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.7e-10,1.7e-10,4.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21190000,0.98,0.0016,-0.0059,0.19,-0.049,0.051,-0.5,-0.0012,0.0036,-0.022,-1.4e-05,-5.9e-05,2.4e-06,0.00014,5.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.4e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21290000,0.98,-0.00055,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0089,-0.081,-1.4e-05,-5.9e-05,2.2e-06,0.00014,4.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.6e-05,9.4e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.15,-1.4e-05,-5.9e-05,2.2e-06,0.00015,1.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.2e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.23,-1.4e-05,-5.9e-05,2.3e-06,0.00015,4.3e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.4e-05,9.3e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.017,-0.32,-1.4e-05,-5.9e-05,2.3e-06,0.00015,8.4e-09,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.2e-05,9e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21690000,0.98,-0.0037,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.43,-1.4e-05,-5.9e-05,2.5e-06,0.00015,-1.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.2e-05,9.1e-05,7e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.55,-1.4e-05,-5.8e-05,2.7e-06,0.00015,-3.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9e-05,8.8e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.69,-1.4e-05,-5.8e-05,2.5e-06,0.00016,-5.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9e-05,8.9e-05,6.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00033,0.017,-0.83,-1.4e-05,-5.8e-05,2.6e-06,0.00015,-2.7e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.8e-05,8.6e-05,6.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +21190000,0.98,0.0016,-0.0059,0.19,-0.049,0.051,-0.5,-0.0012,0.0036,-0.022,-1.4e-05,-5.9e-05,2.4e-06,0.00014,5.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.4e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21290000,0.98,-0.00055,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0089,-0.081,-1.4e-05,-5.9e-05,2.2e-06,0.00014,4.6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.6e-05,9.4e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.15,-1.4e-05,-5.9e-05,2.2e-06,0.00015,1.4e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.2e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.23,-1.4e-05,-5.9e-05,2.3e-06,0.00015,3.7e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.4e-05,9.3e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.017,-0.32,-1.4e-05,-5.9e-05,2.3e-06,0.00015,-5.7e-08,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.2e-05,9e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21690000,0.98,-0.0037,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.43,-1.4e-05,-5.9e-05,2.5e-06,0.00015,-1.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.2e-05,9.1e-05,7e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.55,-1.4e-05,-5.8e-05,2.7e-06,0.00015,-3.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9e-05,8.8e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.69,-1.4e-05,-5.8e-05,2.5e-06,0.00016,-5.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9e-05,8.9e-05,6.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.6e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00033,0.017,-0.83,-1.4e-05,-5.8e-05,2.6e-06,0.00015,-2.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.8e-05,8.6e-05,6.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22090000,0.98,-0.0058,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-0.97,-1.4e-05,-5.8e-05,2.8e-06,0.00015,-4.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.8e-05,8.7e-05,6.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.0061,0.013,-1.1,-1.4e-05,-5.8e-05,2.9e-06,0.00015,-3.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.6e-05,8.5e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.1,-1.4e-05,-5.8e-05,2.9e-06,0.00015,-3.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.6e-05,8.5e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0079,-1.4,0.006,0.014,-1.3,-1.4e-05,-5.8e-05,2.8e-06,0.00016,-4.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.6e-05,8.5e-05,6.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22390000,0.98,-0.0073,-0.01,0.19,0.0066,-0.0017,-1.4,0.013,0.0042,-1.4,-1.4e-05,-5.8e-05,2.6e-06,0.00015,-8.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.5e-05,8.3e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0037,-1.5,-1.4e-05,-5.8e-05,2.5e-06,0.00016,-9.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.5e-05,8.4e-05,6.7e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22590000,0.98,-0.0074,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0052,-1.7,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.3e-05,8.2e-05,6.7e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22690000,0.98,-0.0073,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.8,-1.4e-05,-5.8e-05,2.5e-06,0.00016,-1.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.3e-05,8.2e-05,6.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.5e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22790000,0.98,-0.0073,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.4e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.2e-05,8.1e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-11,8.9e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.034,-1.4,0.041,-0.02,-2.1,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-1.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.2e-05,8.1e-05,6.6e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +22890000,0.98,-0.0075,-0.012,0.19,0.031,-0.034,-1.4,0.041,-0.02,-2.1,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-1.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.2e-05,8.1e-05,6.6e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-1.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.1e-05,8e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.4,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-1.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.1e-05,8e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 23190000,0.98,-0.0075,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-1.4e-05,-5.8e-05,2.6e-06,0.00016,-1.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.5e-05,0.018,0.018,0.008,0.042,0.042,0.035,8e-11,8e-11,2.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 @@ -245,11 +245,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00019,-3.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.2e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,3e-06,0.00019,-3.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 24490000,0.98,-0.0099,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00019,-3.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-11,6.1e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24590000,0.98,-0.011,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00019,-4.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24690000,0.98,-0.011,-0.015,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00019,-4.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +24590000,0.98,-0.011,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00019,-4.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +24690000,0.98,-0.011,-0.015,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00019,-4.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-5.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-5.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00018,-6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00018,-6.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25290000,0.98,-0.011,-0.012,0.18,0.032,-0.051,0.029,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00018,-6.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 @@ -257,13 +257,13 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00018,-7.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.8e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.2e-11,5.2e-11,2.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00018,-7.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00018,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25790000,0.98,-0.011,-0.011,0.18,0.002,-0.03,0.017,0.17,-0.092,-3.5,-1.6e-05,-5.8e-05,2.7e-06,0.00018,-8.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +25790000,0.98,-0.011,-0.011,0.18,0.002,-0.03,0.017,0.17,-0.092,-3.5,-1.6e-05,-5.8e-05,2.7e-06,0.00018,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25890000,0.98,-0.011,-0.011,0.18,-0.0037,-0.028,0.019,0.17,-0.095,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00018,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 25990000,0.98,-0.011,-0.011,0.18,-0.013,-0.022,0.013,0.16,-0.086,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-8.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,1.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 26090000,0.98,-0.011,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-8.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,1.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.013,0.00049,0.15,-0.082,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -26390000,0.98,-0.0099,-0.012,0.18,-0.032,-0.0062,0.0045,0.13,-0.074,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-9.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.013,0.00049,0.15,-0.082,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00019,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +26390000,0.98,-0.0099,-0.012,0.18,-0.032,-0.0062,0.0045,0.13,-0.074,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-9.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0031,0.014,0.13,-0.075,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-9.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.9e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 26590000,0.98,-0.0091,-0.012,0.18,-0.036,0.0048,0.014,0.12,-0.068,-3.5,-1.6e-05,-5.8e-05,2.1e-06,0.00019,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.9e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0099,0.013,0.12,-0.067,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00019,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.9e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 @@ -280,17 +280,17 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 27790000,0.98,-0.0077,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.017,-3.2,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 27890000,0.98,-0.0073,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.1,-1.6e-05,-5.8e-05,1.3e-06,0.0002,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-11,3.8e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 27990000,0.98,-0.0078,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.01,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00019,-9.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0046,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-9.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0042,-0.0046,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-9.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28190000,0.98,-0.0075,-0.012,0.18,-0.082,0.055,0.79,-0.0023,-0.0042,-2.9,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28290000,0.98,-0.007,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0016,-2.8,-1.6e-05,-5.8e-05,1.3e-06,0.00019,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28390000,0.98,-0.007,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0046,-2.8,-1.5e-05,-5.8e-05,1.4e-06,0.00019,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28490000,0.98,-0.0073,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.7,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.2e-05,8e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-11,3.6e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0086,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-9.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0086,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-9.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28690000,0.98,-0.0071,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-9.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00019,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28890000,0.98,-0.0063,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.00019,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +28890000,0.98,-0.0063,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.3,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-9.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29090000,0.98,-0.0059,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.0002,-9.6e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +29090000,0.98,-0.0059,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.0002,-9.7e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-9.8e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.1,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-9.9e-05,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 29390000,0.98,-0.0066,-0.012,0.18,-0.075,0.066,0.78,-0.057,0.034,-2,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-0.0001,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8.1e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 @@ -306,7 +306,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.3,-1.4e-05,-5.7e-05,1.7e-06,0.00021,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.2,-1.4e-05,-5.7e-05,1.8e-06,0.00021,-0.00012,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.3e-05,8.1e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 30590000,0.98,-0.0065,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,1.9e-06,0.00021,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00021,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1,-1.4e-05,-5.7e-05,1.9e-06,0.00022,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 30890000,0.98,-0.0059,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-0.95,-1.4e-05,-5.7e-05,1.8e-06,0.00022,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.041,0.04,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 30990000,0.98,-0.0061,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.88,-1.4e-05,-5.7e-05,1.8e-06,0.00022,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 @@ -318,7 +318,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0067,0.76,-0.038,0.039,-0.45,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 31690000,0.98,-0.006,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.38,-1.4e-05,-5.7e-05,2.1e-06,0.00023,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0031,0.76,-0.028,0.037,-0.31,-1.4e-05,-5.7e-05,2.1e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.6e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.0008,0.76,-0.029,0.038,-0.24,-1.4e-05,-5.7e-05,2.2e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 +31890000,0.98,-0.006,-0.015,0.18,-0.008,0.0008,0.76,-0.029,0.038,-0.24,-1.4e-05,-5.7e-05,2.2e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 31990000,0.98,-0.0062,-0.015,0.18,-0.0001,0.00013,0.75,-0.017,0.035,-0.17,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 32090000,0.98,-0.0066,-0.014,0.18,-0.00064,-0.0033,0.76,-0.017,0.034,-0.1,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8.1e-05,8e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 32190000,0.98,-0.0068,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.037,-1.3e-05,-5.7e-05,2.1e-06,0.00025,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8.1e-05,8e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0