From 84b6b472b44c40553ec0b42dc2edd240a23b97d8 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 28 Jul 2023 09:31:44 -0400 Subject: [PATCH] ekf2: change delta angle and delta velocity bias states to accel and gyro bias (#21901) * ekf2-test: remove outdated codegen comparison The definition of states changed so the comparison with the old derivation cannot work anymore. --------- Co-authored-by: bresch --- src/modules/ekf2/EKF/EKFGSF_yaw.h | 1 - src/modules/ekf2/EKF/common.h | 4 +- src/modules/ekf2/EKF/covariance.cpp | 131 +- src/modules/ekf2/EKF/drag_fusion.cpp | 2 +- src/modules/ekf2/EKF/ekf.cpp | 10 +- src/modules/ekf2/EKF/ekf.h | 18 +- src/modules/ekf2/EKF/ekf_helper.cpp | 43 +- src/modules/ekf2/EKF/estimator_interface.h | 1 - src/modules/ekf2/EKF/gps_yaw_fusion.cpp | 2 +- src/modules/ekf2/EKF/mag_fusion.cpp | 2 +- src/modules/ekf2/EKF/optflow_fusion.cpp | 1 - src/modules/ekf2/EKF/output_predictor.cpp | 3 +- src/modules/ekf2/EKF/output_predictor.h | 3 +- .../EKF/python/ekf_derivation/derivation.py | 24 +- .../generated/predict_covariance.h | 1176 +++++++++-------- src/modules/ekf2/EKF/utils.hpp | 75 -- src/modules/ekf2/EKF/zero_gyro_update.cpp | 8 +- src/modules/ekf2/test/CMakeLists.txt | 1 - .../test/change_indication/ekf_gsf_reset.csv | 780 +++++------ .../ekf2/test/change_indication/iris_gps.csv | 700 +++++----- .../test/sensor_simulator/ekf_wrapper.cpp | 5 - .../ekf2/test/sensor_simulator/ekf_wrapper.h | 2 - .../test_EKF_airspeed_fusion_generated.cpp | 2 +- ...st_EKF_covariance_prediction_generated.cpp | 816 ------------ .../ekf2/test/test_EKF_initialization.cpp | 4 +- src/modules/ekf2/test/test_EKF_utils.cpp | 4 +- .../test/test_EKF_yaw_estimator_generated.cpp | 8 +- 27 files changed, 1452 insertions(+), 2374 deletions(-) delete mode 100644 src/modules/ekf2/EKF/utils.hpp delete mode 100644 src/modules/ekf2/test/test_EKF_covariance_prediction_generated.cpp diff --git a/src/modules/ekf2/EKF/EKFGSF_yaw.h b/src/modules/ekf2/EKF/EKFGSF_yaw.h index f31f430330..c14ab4d9ff 100644 --- a/src/modules/ekf2/EKF/EKFGSF_yaw.h +++ b/src/modules/ekf2/EKF/EKFGSF_yaw.h @@ -39,7 +39,6 @@ #include #include "common.h" -#include "utils.hpp" using matrix::AxisAnglef; using matrix::Dcmf; diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index f20fb37b20..69ab710dd5 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -276,8 +276,8 @@ struct stateSample { Quatf quat_nominal{}; ///< quaternion defining the rotation from body to earth frame Vector3f vel{}; ///< NED velocity in earth frame in m/s Vector3f pos{}; ///< NED position in earth frame in m - Vector3f delta_ang_bias{}; ///< delta angle bias estimate in rad - Vector3f delta_vel_bias{}; ///< delta velocity bias estimate in m/s + Vector3f gyro_bias{}; ///< gyro bias estimate in rad/s + Vector3f accel_bias{}; ///< accel bias estimate in m/s^2 Vector3f mag_I{}; ///< NED earth magnetic field in gauss Vector3f mag_B{}; ///< magnetometer bias estimate in body frame in gauss Vector2f wind_vel{}; ///< horizontal wind velocity in earth frame in m/s diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 86da9086ee..4afa3698bc 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -43,7 +43,6 @@ #include "ekf.h" #include "python/ekf_derivation/generated/predict_covariance.h" -#include "utils.hpp" #include #include @@ -54,11 +53,6 @@ void Ekf::initialiseCovariance() { P.zero(); - _delta_angle_bias_var_accum.setZero(); - _delta_vel_bias_var_accum.setZero(); - - const float dt = _dt_ekf_avg; - resetQuatCov(); // velocity @@ -82,14 +76,14 @@ void Ekf::initialiseCovariance() #endif // CONFIG_EKF2_RANGE_FINDER // gyro bias - _prev_delta_ang_bias_var(0) = P(10,10) = sq(_params.switch_on_gyro_bias * dt); - _prev_delta_ang_bias_var(1) = P(11,11) = P(10,10); - _prev_delta_ang_bias_var(2) = P(12,12) = P(10,10); + _prev_gyro_bias_var(0) = P(10,10) = sq(_params.switch_on_gyro_bias); + _prev_gyro_bias_var(1) = P(11,11) = P(10,10); + _prev_gyro_bias_var(2) = P(12,12) = P(10,10); // accel bias - _prev_dvel_bias_var(0) = P(13,13) = sq(_params.switch_on_accel_bias * dt); - _prev_dvel_bias_var(1) = P(14,14) = P(13,13); - _prev_dvel_bias_var(2) = P(15,15) = P(13,13); + _prev_accel_bias_var(0) = P(13,13) = sq(_params.switch_on_accel_bias); + _prev_accel_bias_var(1) = P(14,14) = P(13,13); + _prev_accel_bias_var(2) = P(15,15) = P(13,13); resetMagCov(); @@ -105,12 +99,6 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) const float dt = _dt_ekf_avg; const float dt_inv = 1.f / dt; - // convert rate of change of rate gyro bias (rad/s**2) as specified by the parameter to an expected change in delta angle (rad) since the last update - const float d_ang_bias_sig = dt * dt * math::constrain(_params.gyro_bias_p_noise, 0.0f, 1.0f); - - // convert rate of change of accelerometer bias (m/s**3) as specified by the parameter to an expected change in delta velocity (m/s) since the last update - const float d_vel_bias_sig = dt * dt * math::constrain(_params.accel_bias_p_noise, 0.0f, 1.0f); - // inhibit learning of imu accel bias if the manoeuvre levels are too high to protect against the effect of sensor nonlinearities or bad accel data is detected // xy accel bias learning is also disabled on ground as those states are poorly observable when perpendicular to the gravity vector const float alpha = math::constrain((dt / _params.acc_bias_learn_tc), 0.0f, 1.0f); @@ -137,14 +125,14 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) if (do_inhibit_axis) { // store the bias state variances to be reinstated later if (!_gyro_bias_inhibit[index]) { - _prev_delta_ang_bias_var(index) = P(stateIndex, stateIndex); + _prev_gyro_bias_var(index) = P(stateIndex, stateIndex); _gyro_bias_inhibit[index] = true; } } else { if (_gyro_bias_inhibit[index]) { // reinstate the bias state variances - P(stateIndex, stateIndex) = _prev_delta_ang_bias_var(index); + P(stateIndex, stateIndex) = _prev_gyro_bias_var(index); _gyro_bias_inhibit[index] = false; } } @@ -176,14 +164,14 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) if (do_inhibit_axis) { // store the bias state variances to be reinstated later if (!_accel_bias_inhibit[index]) { - _prev_dvel_bias_var(index) = P(stateIndex, stateIndex); + _prev_accel_bias_var(index) = P(stateIndex, stateIndex); _accel_bias_inhibit[index] = true; } } else { if (_accel_bias_inhibit[index]) { // reinstate the bias state variances - P(stateIndex, stateIndex) = _prev_dvel_bias_var(index); + P(stateIndex, stateIndex) = _prev_accel_bias_var(index); _accel_bias_inhibit[index] = false; } } @@ -223,22 +211,6 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) wind_vel_nsd_scaled = 0.0f; } - // compute noise variance for stationary processes - Vector24f process_noise; - - // Construct the process noise variance diagonal for those states with a stationary process model - // These are kinematic states and their error growth is controlled separately by the IMU noise variances - - // delta angle bias states - process_noise.slice<3, 1>(10, 0) = sq(d_ang_bias_sig); - // delta_velocity bias states - process_noise.slice<3, 1>(13, 0) = sq(d_vel_bias_sig); - // earth frame magnetic field states - process_noise.slice<3, 1>(16, 0) = sq(mag_I_sig); - // body frame magnetic field states - process_noise.slice<3, 1>(19, 0) = sq(mag_B_sig); - // wind velocity states - process_noise.slice<2, 1>(22, 0) = sq(wind_vel_nsd_scaled) * dt; // assign IMU noise variances // inputs to the system are 3 delta angles and 3 delta velocities @@ -265,43 +237,52 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // calculate variances and upper diagonal covariances for quaternion, velocity, position and gyro bias states sym::PredictCovariance(getStateAtFusionHorizonAsVector(), P, imu_delayed.delta_vel, d_vel_var, imu_delayed.delta_ang, d_ang_var, dt, &nextP); - // process noise contribution for delta angle states can be very small compared to - // the variances, therefore use algorithm to minimise numerical error - for (unsigned i = 10; i <= 12; i++) { - const int index = i - 10; + // compute noise variance for stationary processes + Vector24f process_noise; - if (!_gyro_bias_inhibit[index]) { - // add process noise that is not from the IMU - // process noise contribution for delta velocity states can be very small compared to - // the variances, therefore use algorithm to minimise numerical error - nextP(i, i) = kahanSummation(nextP(i, i), process_noise(i), _delta_angle_bias_var_accum(index)); + // Construct the process noise variance diagonal for those states with a stationary process model + // These are kinematic states and their error growth is controlled separately by the IMU noise variances - } else { - nextP.uncorrelateCovarianceSetVariance<1>(i, _prev_delta_ang_bias_var(index)); - _delta_angle_bias_var_accum(index) = 0.f; - } - } - - for (int i = 13; i <= 15; i++) { - const int index = i - 13; - - if (!_accel_bias_inhibit[index]) { - // add process noise that is not from the IMU - // process noise contribution for delta velocity states can be very small compared to - // the variances, therefore use algorithm to minimise numerical error - nextP(i, i) = kahanSummation(nextP(i, i), process_noise(i), _delta_vel_bias_var_accum(index)); - - } else { - nextP.uncorrelateCovarianceSetVariance<1>(i, _prev_dvel_bias_var(index)); - _delta_vel_bias_var_accum(index) = 0.f; - } - } + // earth frame magnetic field states + process_noise.slice<3, 1>(16, 0) = sq(mag_I_sig); + // body frame magnetic field states + process_noise.slice<3, 1>(19, 0) = sq(mag_B_sig); + // wind velocity states + process_noise.slice<2, 1>(22, 0) = sq(wind_vel_nsd_scaled) * dt; // add process noise that is not from the IMU for (unsigned i = 16; i <= 23; i++) { nextP(i, i) += process_noise(i); } + // gyro bias: add process noise, or restore previous gyro bias var if state inhibited + const float gyro_bias_sig = dt * math::constrain(_params.gyro_bias_p_noise, 0.f, 1.f); + const float gyro_bias_process_noise = sq(gyro_bias_sig); + for (unsigned i = 10; i <= 12; i++) { + const int axis_index = i - 10; + + if (!_gyro_bias_inhibit[axis_index]) { + nextP(i, i) += gyro_bias_process_noise; + + } else { + nextP.uncorrelateCovarianceSetVariance<1>(i, _prev_gyro_bias_var(axis_index)); + } + } + + // accel bias: add process noise, or restore previous accel bias var if state inhibited + const float accel_bias_sig = dt * math::constrain(_params.accel_bias_p_noise, 0.f, 1.f); + const float accel_bias_process_noise = sq(accel_bias_sig); + for (int i = 13; i <= 15; i++) { + const int axis_index = i - 13; + + if (!_accel_bias_inhibit[axis_index]) { + nextP(i, i) += accel_bias_process_noise; + + } else { + nextP.uncorrelateCovarianceSetVariance<1>(i, _prev_accel_bias_var(axis_index)); + } + } + // covariance matrix is symmetrical, so copy upper half to lower half for (unsigned row = 0; row <= 15; row++) { for (unsigned column = 0 ; column < row; column++) { @@ -385,7 +366,7 @@ void Ekf::fixCovarianceErrors(bool force_symmetry) // accelerometer bias states if (!_accel_bias_inhibit[0] || !_accel_bias_inhibit[1] || !_accel_bias_inhibit[2]) { // Find the maximum delta velocity bias state variance and request a covariance reset if any variance is below the safe minimum - const float minSafeStateVar = 1e-9f; + const float minSafeStateVar = 1e-9f / sq(_dt_ekf_avg); float maxStateVar = minSafeStateVar; bool resetRequired = false; @@ -406,7 +387,7 @@ void Ekf::fixCovarianceErrors(bool force_symmetry) // To ensure stability of the covariance matrix operations, the ratio of a max and min variance must // not exceed 100 and the minimum variance must not fall below the target minimum // Also limit variance to a maximum equivalent to a 0.1g uncertainty - const float minStateVarTarget = 5E-8f; + const float minStateVarTarget = 5E-8f / sq(_dt_ekf_avg); float minAllowedStateVar = fmaxf(0.01f * maxStateVar, minStateVarTarget); for (uint8_t stateIndex = 13; stateIndex <= 15; stateIndex++) { @@ -415,8 +396,7 @@ void Ekf::fixCovarianceErrors(bool force_symmetry) continue; } - P(stateIndex, stateIndex) = math::constrain(P(stateIndex, stateIndex), minAllowedStateVar, - sq(0.1f * CONSTANTS_ONE_G * _dt_ekf_avg)); + P(stateIndex, stateIndex) = math::constrain(P(stateIndex, stateIndex), minAllowedStateVar, sq(0.1f * CONSTANTS_ONE_G)); } // If any one axis has fallen below the safe minimum, all delta velocity covariance terms must be reset to zero @@ -427,7 +407,8 @@ void Ekf::fixCovarianceErrors(bool force_symmetry) // Run additional checks to see if the delta velocity bias has hit limits in a direction that is clearly wrong // calculate accel bias term aligned with the gravity vector const float dVel_bias_lim = 0.9f * _params.acc_bias_lim * _dt_ekf_avg; - const float down_dvel_bias = _state.delta_vel_bias.dot(Vector3f(_R_to_earth.row(2))); + const Vector3f delta_vel_bias = _state.accel_bias * _dt_ekf_avg; + const float down_dvel_bias = delta_vel_bias.dot(Vector3f(_R_to_earth.row(2))); // check that the vertical component of accel bias is consistent with both the vertical position and velocity innovation bool bad_acc_bias = false; @@ -602,9 +583,9 @@ void Ekf::zeroMagCov() P.uncorrelateCovarianceSetVariance<3>(19, 0.0f); } -void Ekf::resetZDeltaAngBiasCov() +void Ekf::resetGyroBiasZCov() { - const float init_delta_ang_bias_var = sq(_params.switch_on_gyro_bias * _dt_ekf_avg); + const float init_gyro_bias_var = sq(_params.switch_on_gyro_bias); - P.uncorrelateCovarianceSetVariance<1>(12, init_delta_ang_bias_var); + P.uncorrelateCovarianceSetVariance<1>(12, init_gyro_bias_var); } diff --git a/src/modules/ekf2/EKF/drag_fusion.cpp b/src/modules/ekf2/EKF/drag_fusion.cpp index ca15715b7c..ce7730d938 100644 --- a/src/modules/ekf2/EKF/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/drag_fusion.cpp @@ -110,7 +110,7 @@ void Ekf::fuseDrag(const dragSample &drag_sample) // perform sequential fusion of XY specific forces for (uint8_t axis_index = 0; axis_index < 2; axis_index++) { // measured drag acceleration corrected for sensor bias - const float mea_acc = drag_sample.accelXY(axis_index) - _state.delta_vel_bias(axis_index) / _dt_ekf_avg; + const float mea_acc = drag_sample.accelXY(axis_index) - _state.accel_bias(axis_index); // Drag is modelled as an arbitrary combination of bluff body drag that proportional to // equivalent airspeed squared, and rotor momentum drag that is proportional to true airspeed diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index f078a53690..97ad3117e3 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -56,8 +56,8 @@ void Ekf::reset() _state.vel.setZero(); _state.pos.setZero(); - _state.delta_ang_bias.setZero(); - _state.delta_vel_bias.setZero(); + _state.gyro_bias.setZero(); + _state.accel_bias.setZero(); _state.mag_I.setZero(); _state.mag_B.setZero(); _state.wind_vel.setZero(); @@ -80,7 +80,8 @@ void Ekf::reset() _fault_status.value = 0; _innov_check_fail_status.value = 0; - _prev_dvel_bias_var.zero(); + _prev_gyro_bias_var.zero(); + _prev_accel_bias_var.zero(); resetGpsDriftCheckFilters(); @@ -185,8 +186,7 @@ bool Ekf::update() runTerrainEstimator(imu_sample_delayed); #endif // CONFIG_EKF2_RANGE_FINDER - _output_predictor.correctOutputStates(imu_sample_delayed.time_us, getGyroBias(), getAccelBias(), - _state.quat_nominal, _state.vel, _state.pos); + _output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, _state.gyro_bias, _state.accel_bias); return true; } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index d242f6440b..774bae5fac 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -363,13 +363,13 @@ public: } // gyro bias (states 10, 11, 12) - Vector3f getGyroBias() const { return _state.delta_ang_bias / _dt_ekf_avg; } // get the gyroscope bias in rad/s - Vector3f getGyroBiasVariance() const { return Vector3f{P(10, 10), P(11, 11), P(12, 12)} / sq(_dt_ekf_avg); } // get the gyroscope bias variance in rad/s + const Vector3f &getGyroBias() const { return _state.gyro_bias; } // get the gyroscope bias in rad/s + Vector3f getGyroBiasVariance() const { return Vector3f{P(10, 10), P(11, 11), P(12, 12)}; } // get the gyroscope bias variance in rad/s float getGyroBiasLimit() const { return _params.gyro_bias_lim; } // accel bias (states 13, 14, 15) - Vector3f getAccelBias() const { return _state.delta_vel_bias / _dt_ekf_avg; } // get the accelerometer bias in m/s**2 - Vector3f getAccelBiasVariance() const { return Vector3f{P(13, 13), P(14, 14), P(15, 15)} / sq(_dt_ekf_avg); } // get the accelerometer bias variance in m/s**2 + const Vector3f &getAccelBias() const { return _state.accel_bias; } // get the accelerometer bias in m/s**2 + Vector3f getAccelBiasVariance() const { return Vector3f{P(13, 13), P(14, 14), P(15, 15)}; } // get the accelerometer bias variance in m/s**2 float getAccelBiasLimit() const { return _params.acc_bias_lim; } const Vector3f &getMagEarthField() const { return _state.mag_I; } @@ -589,9 +589,6 @@ private: SquareMatrix24f P{}; ///< state covariance matrix - Vector3f _delta_angle_bias_var_accum{}; ///< kahan summation algorithm accumulator for delta angle bias variance - Vector3f _delta_vel_bias_var_accum{}; ///< kahan summation algorithm accumulator for delta velocity bias variance - #if defined(CONFIG_EKF2_DRAG_FUSION) Vector2f _drag_innov{}; ///< multirotor drag measurement innovation (m/sec**2) Vector2f _drag_innov_var{}; ///< multirotor drag measurement innovation variance ((m/sec**2)**2) @@ -721,8 +718,9 @@ private: Vector3f _accel_vec_filt{}; ///< acceleration vector after application of a low pass filter (m/sec**2) float _accel_magnitude_filt{0.0f}; ///< acceleration magnitude after application of a decaying envelope filter (rad/sec) float _ang_rate_magnitude_filt{0.0f}; ///< angular rate magnitude after application of a decaying envelope filter (rad/sec) - Vector3f _prev_delta_ang_bias_var{}; ///< saved delta angle XYZ bias variances (rad/sec) - Vector3f _prev_dvel_bias_var{}; ///< saved delta velocity XYZ bias variances (m/sec)**2 + + Vector3f _prev_gyro_bias_var{}; ///< saved gyro XYZ bias variances + Vector3f _prev_accel_bias_var{}; ///< saved accel XYZ bias variances // height sensor status bool _baro_hgt_faulty{false}; ///< true if baro data have been declared faulty TODO: move to fault flags @@ -1110,7 +1108,7 @@ private: void clearMagCov(); void zeroMagCov(); - void resetZDeltaAngBiasCov(); + void resetGyroBiasZCov(); // uncorrelate quaternion states from other states void uncorrelateQuatFromOtherStates(); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 6c2754760a..34e86bf4b5 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -224,11 +224,11 @@ void Ekf::constrainStates() _state.vel = matrix::constrain(_state.vel, -1000.0f, 1000.0f); _state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f); - const float delta_ang_bias_limit = getGyroBiasLimit() * _dt_ekf_avg; - _state.delta_ang_bias = matrix::constrain(_state.delta_ang_bias, -delta_ang_bias_limit, delta_ang_bias_limit); + const float gyro_bias_limit = getGyroBiasLimit(); + _state.gyro_bias = matrix::constrain(_state.gyro_bias, -gyro_bias_limit, gyro_bias_limit); - const float delta_vel_bias_limit = getAccelBiasLimit() * _dt_ekf_avg; - _state.delta_vel_bias = matrix::constrain(_state.delta_vel_bias, -delta_vel_bias_limit, delta_vel_bias_limit); + const float accel_bias_limit = getAccelBiasLimit(); + _state.accel_bias = matrix::constrain(_state.accel_bias, -accel_bias_limit, accel_bias_limit); _state.mag_I = matrix::constrain(_state.mag_I, -1.0f, 1.0f); _state.mag_B = matrix::constrain(_state.mag_B, -getMagBiasLimit(), getMagBiasLimit()); @@ -390,8 +390,8 @@ matrix::Vector Ekf::getStateAtFusionHorizonAsVector() const state.slice<4, 1>(0, 0) = _state.quat_nominal; state.slice<3, 1>(4, 0) = _state.vel; state.slice<3, 1>(7, 0) = _state.pos; - state.slice<3, 1>(10, 0) = _state.delta_ang_bias; - state.slice<3, 1>(13, 0) = _state.delta_vel_bias; + state.slice<3, 1>(10, 0) = _state.gyro_bias; + state.slice<3, 1>(13, 0) = _state.accel_bias; state.slice<3, 1>(16, 0) = _state.mag_I; state.slice<3, 1>(19, 0) = _state.mag_B; state.slice<2, 1>(22, 0) = _state.wind_vel; @@ -612,25 +612,28 @@ void Ekf::resetImuBias() void Ekf::resetGyroBias() { - // Zero the delta angle and delta velocity bias states - _state.delta_ang_bias.zero(); + // Zero the gyro bias states + _state.gyro_bias.zero(); // Zero the corresponding covariances and set // variances to the values use for initial alignment - P.uncorrelateCovarianceSetVariance<3>(10, sq(_params.switch_on_gyro_bias * _dt_ekf_avg)); + P.uncorrelateCovarianceSetVariance<3>(10, sq(_params.switch_on_gyro_bias)); + + // Set previous frame values + _prev_gyro_bias_var = P.slice<3, 3>(10, 10).diag(); } void Ekf::resetAccelBias() { - // Zero the delta angle and delta velocity bias states - _state.delta_vel_bias.zero(); + // Zero the accel bias states + _state.accel_bias.zero(); // Zero the corresponding covariances and set // variances to the values use for initial alignment - P.uncorrelateCovarianceSetVariance<3>(13, sq(_params.switch_on_accel_bias * _dt_ekf_avg)); + P.uncorrelateCovarianceSetVariance<3>(13, sq(_params.switch_on_accel_bias)); // Set previous frame values - _prev_dvel_bias_var = P.slice<3, 3>(13, 13).diag(); + _prev_accel_bias_var = P.slice<3, 3>(13, 13).diag(); } // get EKF innovation consistency check status information comprising of: @@ -792,13 +795,13 @@ void Ekf::fuse(const Vector24f &K, float innovation) _state.quat_nominal.normalize(); _R_to_earth = Dcmf(_state.quat_nominal); - _state.vel -= K.slice<3, 1>(4, 0) * innovation; - _state.pos -= K.slice<3, 1>(7, 0) * innovation; - _state.delta_ang_bias -= K.slice<3, 1>(10, 0) * innovation; - _state.delta_vel_bias -= K.slice<3, 1>(13, 0) * innovation; - _state.mag_I -= K.slice<3, 1>(16, 0) * innovation; - _state.mag_B -= K.slice<3, 1>(19, 0) * innovation; - _state.wind_vel -= K.slice<2, 1>(22, 0) * innovation; + _state.vel -= K.slice<3, 1>(4, 0) * innovation; + _state.pos -= K.slice<3, 1>(7, 0) * innovation; + _state.gyro_bias -= K.slice<3, 1>(10, 0) * innovation; + _state.accel_bias -= K.slice<3, 1>(13, 0) * innovation; + _state.mag_I -= K.slice<3, 1>(16, 0) * innovation; + _state.mag_B -= K.slice<3, 1>(19, 0) * innovation; + _state.wind_vel -= K.slice<2, 1>(22, 0) * innovation; } void Ekf::uncorrelateQuatFromOtherStates() diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 9ac957292a..ed01ca3000 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -64,7 +64,6 @@ #include "common.h" #include "RingBuffer.h" #include "imu_down_sampler.hpp" -#include "utils.hpp" #include "output_predictor.h" #if defined(CONFIG_EKF2_RANGE_FINDER) diff --git a/src/modules/ekf2/EKF/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/gps_yaw_fusion.cpp index 7ddfb391ee..9deffe1e5f 100644 --- a/src/modules/ekf2/EKF/gps_yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/gps_yaw_fusion.cpp @@ -126,7 +126,7 @@ void Ekf::fuseGpsYaw() // A constant large signed test ratio is a sign of wrong gyro bias // Reset the yaw gyro variance to converge faster and avoid // being stuck on a previous bad estimate - resetZDeltaAngBiasCov(); + resetGyroBiasZCov(); } // calculate the Kalman gains diff --git a/src/modules/ekf2/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/mag_fusion.cpp index 2e0f2977c5..0fc53b7190 100644 --- a/src/modules/ekf2/EKF/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/mag_fusion.cpp @@ -296,7 +296,7 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s& aid_src_status, const Vector24f &H_Y // also reset the yaw gyro variance to converge faster and avoid // being stuck on a previous bad estimate - resetZDeltaAngBiasCov(); + resetGyroBiasZCov(); } else { return false; diff --git a/src/modules/ekf2/EKF/optflow_fusion.cpp b/src/modules/ekf2/EKF/optflow_fusion.cpp index 0f179233cb..243edabfe7 100644 --- a/src/modules/ekf2/EKF/optflow_fusion.cpp +++ b/src/modules/ekf2/EKF/optflow_fusion.cpp @@ -47,7 +47,6 @@ #include #include "python/ekf_derivation/generated/compute_flow_xy_innov_var_and_hx.h" #include "python/ekf_derivation/generated/compute_flow_y_innov_var_and_h.h" -#include "utils.hpp" void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) { diff --git a/src/modules/ekf2/EKF/output_predictor.cpp b/src/modules/ekf2/EKF/output_predictor.cpp index bdb8077ea0..123ec83fa9 100644 --- a/src/modules/ekf2/EKF/output_predictor.cpp +++ b/src/modules/ekf2/EKF/output_predictor.cpp @@ -240,8 +240,7 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector } 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 Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias) { // calculate an average filter update time if (_time_last_correct_states_us != 0) { diff --git a/src/modules/ekf2/EKF/output_predictor.h b/src/modules/ekf2/EKF/output_predictor.h index 5eb3b44e2f..4acded9c34 100644 --- a/src/modules/ekf2/EKF/output_predictor.h +++ b/src/modules/ekf2/EKF/output_predictor.h @@ -68,8 +68,7 @@ public: 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); + const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias); void resetQuaternion(const matrix::Quatf &quat_change); diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py index 9921c28506..5b1c4c59ec 100755 --- a/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/derivation.py @@ -50,12 +50,12 @@ class State: px = 7 py = 8 pz = 9 - d_ang_bx = 10 - d_ang_by = 11 - d_ang_bz = 12 - d_vel_bx = 13 - d_vel_by = 14 - d_vel_bz = 15 + gyro_bx = 10 + gyro_by = 11 + gyro_bz = 12 + accel_bx = 13 + accel_by = 14 + accel_bz = 15 ix = 16 iy = 17 iz = 18 @@ -89,10 +89,12 @@ def predict_covariance( ): g = sf.Symbol("g") # does not appear in the jacobians - d_vel_b = sf.V3(state[State.d_vel_bx], state[State.d_vel_by], state[State.d_vel_bz]) + accel_b = sf.V3(state[State.accel_bx], state[State.accel_by], state[State.accel_bz]) + d_vel_b = accel_b * dt d_vel_true = d_vel - d_vel_b - d_ang_b = sf.V3(state[State.d_ang_bx], state[State.d_ang_by], state[State.d_ang_bz]) + gyro_b = sf.V3(state[State.gyro_bx], state[State.gyro_by], state[State.gyro_bz]) + d_ang_b = gyro_b * dt d_ang_true = d_ang - d_ang_b q = state_to_quat(state) @@ -100,12 +102,12 @@ def predict_covariance( v = sf.V3(state[State.vx], state[State.vy], state[State.vz]) p = sf.V3(state[State.px], state[State.py], state[State.pz]) - q_new = q * sf.Quaternion(sf.V3(0.5 * d_ang_true[0], 0.5 * d_ang_true[1], 0.5 * d_ang_true[2]), 1) - v_new = v + R_to_earth * d_vel_true + sf.V3(0 ,0 ,g) * dt + q_new = q * sf.Quaternion(sf.V3(0.5 * d_ang_true[0], 0.5 * d_ang_true[1], 0.5 * d_ang_true[2]), 1) + v_new = v + R_to_earth * d_vel_true + sf.V3(0, 0, g) * dt p_new = p + v * dt # Predicted state vector at time t + dt - state_new = VState.block_matrix([[sf.V4(q_new.w, q_new.x, q_new.y, q_new.z)], [v_new], [p_new], [sf.Matrix(state[State.d_ang_bx:State.n_states])]]) + state_new = VState.block_matrix([[sf.V4(q_new.w, q_new.x, q_new.y, q_new.z)], [v_new], [p_new], [sf.Matrix(state[State.gyro_bx:State.n_states])]]) # State propagation jacobian A = state_new.jacobian(state) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h index ef62b47bd3..a24f06b065 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h @@ -34,287 +34,290 @@ void PredictCovariance(const matrix::Matrix& state, const matrix::Matrix& d_vel_var, const matrix::Matrix& d_ang, const Scalar d_ang_var, const Scalar dt, matrix::Matrix* const P_new = nullptr) { - // Total ops: 2876 + // Total ops: 2882 // Input arrays - // Intermediate terms (171) - const Scalar _tmp0 = Scalar(0.5) * d_ang(2, 0); - const Scalar _tmp1 = Scalar(0.5) * state(12, 0); - const Scalar _tmp2 = -_tmp0 + _tmp1; - const Scalar _tmp3 = Scalar(0.5) * d_ang(1, 0); - const Scalar _tmp4 = Scalar(0.5) * state(11, 0); - const Scalar _tmp5 = -_tmp3 + _tmp4; - const Scalar _tmp6 = Scalar(0.5) * d_ang(0, 0); - const Scalar _tmp7 = Scalar(0.5) * state(10, 0); - const Scalar _tmp8 = -_tmp6 + _tmp7; - const Scalar _tmp9 = Scalar(0.5) * state(3, 0); - const Scalar _tmp10 = Scalar(0.5) * state(2, 0); - const Scalar _tmp11 = Scalar(0.5) * state(1, 0); - const Scalar _tmp12 = P(0, 11) + P(1, 11) * _tmp8 + P(10, 11) * _tmp11 + P(11, 11) * _tmp10 + - P(12, 11) * _tmp9 + P(2, 11) * _tmp5 + P(3, 11) * _tmp2; - const Scalar _tmp13 = P(0, 10) + P(1, 10) * _tmp8 + P(10, 10) * _tmp11 + P(11, 10) * _tmp10 + - P(12, 10) * _tmp9 + P(2, 10) * _tmp5 + P(3, 10) * _tmp2; - const Scalar _tmp14 = P(0, 12) + P(1, 12) * _tmp8 + P(10, 12) * _tmp11 + P(11, 12) * _tmp10 + - P(12, 12) * _tmp9 + P(2, 12) * _tmp5 + P(3, 12) * _tmp2; - const Scalar _tmp15 = P(0, 2) + P(1, 2) * _tmp8 + P(10, 2) * _tmp11 + P(11, 2) * _tmp10 + - P(12, 2) * _tmp9 + P(2, 2) * _tmp5 + P(3, 2) * _tmp2; - const Scalar _tmp16 = Scalar(0.5) * P(11, 3); - const Scalar _tmp17 = P(0, 3) + P(1, 3) * _tmp8 + P(10, 3) * _tmp11 + P(12, 3) * _tmp9 + - P(2, 3) * _tmp5 + P(3, 3) * _tmp2 + _tmp16 * state(2, 0); - const Scalar _tmp18 = Scalar(0.5) * P(11, 1); - const Scalar _tmp19 = P(0, 1) + P(1, 1) * _tmp8 + P(10, 1) * _tmp11 + P(12, 1) * _tmp9 + - P(2, 1) * _tmp5 + P(3, 1) * _tmp2 + _tmp18 * state(2, 0); - const Scalar _tmp20 = std::pow(state(3, 0), Scalar(2)); - const Scalar _tmp21 = Scalar(0.25) * d_ang_var; - const Scalar _tmp22 = _tmp20 * _tmp21; - const Scalar _tmp23 = Scalar(0.5) * P(11, 0); - const Scalar _tmp24 = P(0, 0) + P(1, 0) * _tmp8 + P(10, 0) * _tmp11 + P(12, 0) * _tmp9 + - P(2, 0) * _tmp5 + P(3, 0) * _tmp2 + _tmp23 * state(2, 0); + // Intermediate terms (174) + const Scalar _tmp0 = Scalar(0.5) * d_ang(0, 0); + const Scalar _tmp1 = Scalar(0.5) * dt; + const Scalar _tmp2 = _tmp1 * state(10, 0); + const Scalar _tmp3 = -_tmp0 + _tmp2; + const Scalar _tmp4 = Scalar(0.5) * d_ang(2, 0); + const Scalar _tmp5 = _tmp1 * state(12, 0); + const Scalar _tmp6 = -_tmp4 + _tmp5; + const Scalar _tmp7 = Scalar(0.5) * d_ang(1, 0); + const Scalar _tmp8 = _tmp1 * state(11, 0); + const Scalar _tmp9 = -_tmp7 + _tmp8; + const Scalar _tmp10 = _tmp1 * state(2, 0); + const Scalar _tmp11 = _tmp1 * state(3, 0); + const Scalar _tmp12 = _tmp1 * state(1, 0); + const Scalar _tmp13 = P(0, 12) + P(1, 12) * _tmp3 + P(10, 12) * _tmp12 + P(11, 12) * _tmp10 + + P(12, 12) * _tmp11 + P(2, 12) * _tmp9 + P(3, 12) * _tmp6; + const Scalar _tmp14 = P(0, 11) + P(1, 11) * _tmp3 + P(10, 11) * _tmp12 + P(11, 11) * _tmp10 + + P(12, 11) * _tmp11 + P(2, 11) * _tmp9 + P(3, 11) * _tmp6; + const Scalar _tmp15 = P(0, 10) + P(1, 10) * _tmp3 + P(10, 10) * _tmp12 + P(11, 10) * _tmp10 + + P(12, 10) * _tmp11 + P(2, 10) * _tmp9 + P(3, 10) * _tmp6; + const Scalar _tmp16 = P(0, 2) + P(1, 2) * _tmp3 + P(10, 2) * _tmp12 + P(11, 2) * _tmp10 + + P(12, 2) * _tmp11 + P(2, 2) * _tmp9 + P(3, 2) * _tmp6; + const Scalar _tmp17 = P(0, 1) + P(1, 1) * _tmp3 + P(10, 1) * _tmp12 + P(11, 1) * _tmp10 + + P(12, 1) * _tmp11 + P(2, 1) * _tmp9 + P(3, 1) * _tmp6; + const Scalar _tmp18 = P(0, 3) + P(1, 3) * _tmp3 + P(10, 3) * _tmp12 + P(11, 3) * _tmp10 + + P(12, 3) * _tmp11 + P(2, 3) * _tmp9 + P(3, 3) * _tmp6; + const Scalar _tmp19 = std::pow(state(1, 0), Scalar(2)); + const Scalar _tmp20 = Scalar(0.25) * d_ang_var; + const Scalar _tmp21 = _tmp19 * _tmp20; + const Scalar _tmp22 = P(0, 0) + P(1, 0) * _tmp3 + P(10, 0) * _tmp12 + P(11, 0) * _tmp10 + + P(12, 0) * _tmp11 + P(2, 0) * _tmp9 + P(3, 0) * _tmp6; + const Scalar _tmp23 = std::pow(state(3, 0), Scalar(2)); + const Scalar _tmp24 = _tmp20 * _tmp23; const Scalar _tmp25 = std::pow(state(2, 0), Scalar(2)); - const Scalar _tmp26 = _tmp21 * _tmp25; - const Scalar _tmp27 = std::pow(state(1, 0), Scalar(2)); - const Scalar _tmp28 = _tmp21 * _tmp27; - const Scalar _tmp29 = _tmp26 + _tmp28; - const Scalar _tmp30 = Scalar(0.5) * state(0, 0); - const Scalar _tmp31 = _tmp21 * state(0, 0); - const Scalar _tmp32 = _tmp0 - _tmp1; - const Scalar _tmp33 = _tmp6 - _tmp7; - const Scalar _tmp34 = P(0, 12) * _tmp33 + P(1, 12) - P(10, 12) * _tmp30 + P(11, 12) * _tmp9 - - P(12, 12) * _tmp10 + P(2, 12) * _tmp32 + P(3, 12) * _tmp5; - const Scalar _tmp35 = P(0, 11) * _tmp33 + P(1, 11) - P(10, 11) * _tmp30 + P(11, 11) * _tmp9 - - P(12, 11) * _tmp10 + P(2, 11) * _tmp32 + P(3, 11) * _tmp5; - const Scalar _tmp36 = P(0, 10) * _tmp33 + P(1, 10) - P(10, 10) * _tmp30 + P(11, 10) * _tmp9 - - P(12, 10) * _tmp10 + P(2, 10) * _tmp32 + P(3, 10) * _tmp5; - const Scalar _tmp37 = P(0, 3) * _tmp33 + P(1, 3) - P(10, 3) * _tmp30 + P(11, 3) * _tmp9 - - P(12, 3) * _tmp10 + P(2, 3) * _tmp32 + P(3, 3) * _tmp5; - const Scalar _tmp38 = P(0, 2) * _tmp33 + P(1, 2) - P(10, 2) * _tmp30 + P(11, 2) * _tmp9 - - P(12, 2) * _tmp10 + P(2, 2) * _tmp32 + P(3, 2) * _tmp5; - const Scalar _tmp39 = P(0, 0) * _tmp33 + P(1, 0) - P(10, 0) * _tmp30 - P(12, 0) * _tmp10 + - P(2, 0) * _tmp32 + P(3, 0) * _tmp5 + _tmp23 * state(3, 0); - const Scalar _tmp40 = P(0, 1) * _tmp33 + P(1, 1) - P(10, 1) * _tmp30 - P(12, 1) * _tmp10 + - P(2, 1) * _tmp32 + P(3, 1) * _tmp5 + _tmp18 * state(3, 0); - const Scalar _tmp41 = _tmp21 * std::pow(state(0, 0), Scalar(2)); - const Scalar _tmp42 = _tmp22 + _tmp41; - const Scalar _tmp43 = _tmp3 - _tmp4; - const Scalar _tmp44 = P(0, 12) * _tmp43 + P(1, 12) * _tmp2 - P(10, 12) * _tmp9 - - P(11, 12) * _tmp30 + P(12, 12) * _tmp11 + P(2, 12) + P(3, 12) * _tmp33; - const Scalar _tmp45 = P(0, 11) * _tmp43 + P(1, 11) * _tmp2 - P(10, 11) * _tmp9 - - P(11, 11) * _tmp30 + P(12, 11) * _tmp11 + P(2, 11) + P(3, 11) * _tmp33; - const Scalar _tmp46 = P(0, 10) * _tmp43 + P(1, 10) * _tmp2 - P(10, 10) * _tmp9 - - P(11, 10) * _tmp30 + P(12, 10) * _tmp11 + P(2, 10) + P(3, 10) * _tmp33; - const Scalar _tmp47 = P(0, 0) * _tmp43 + P(1, 0) * _tmp2 - P(10, 0) * _tmp9 + P(12, 0) * _tmp11 + - P(2, 0) + P(3, 0) * _tmp33 - _tmp23 * state(0, 0); - const Scalar _tmp48 = P(0, 1) * _tmp43 + P(1, 1) * _tmp2 - P(10, 1) * _tmp9 + P(12, 1) * _tmp11 + - P(2, 1) + P(3, 1) * _tmp33 - _tmp18 * state(0, 0); - const Scalar _tmp49 = P(0, 3) * _tmp43 + P(1, 3) * _tmp2 - P(10, 3) * _tmp9 + P(12, 3) * _tmp11 + - P(2, 3) + P(3, 3) * _tmp33 - _tmp16 * state(0, 0); - const Scalar _tmp50 = P(0, 2) * _tmp43 + P(1, 2) * _tmp2 - P(10, 2) * _tmp9 - P(11, 2) * _tmp30 + - P(12, 2) * _tmp11 + P(2, 2) + P(3, 2) * _tmp33; - const Scalar _tmp51 = _tmp21 * state(3, 0); - const Scalar _tmp52 = P(0, 12) * _tmp32 + P(1, 12) * _tmp43 + P(10, 12) * _tmp10 - - P(11, 12) * _tmp11 - P(12, 12) * _tmp30 + P(2, 12) * _tmp8 + P(3, 12); - const Scalar _tmp53 = P(0, 11) * _tmp32 + P(1, 11) * _tmp43 + P(10, 11) * _tmp10 - - P(11, 11) * _tmp11 - P(12, 11) * _tmp30 + P(2, 11) * _tmp8 + P(3, 11); - const Scalar _tmp54 = P(0, 10) * _tmp32 + P(1, 10) * _tmp43 + P(10, 10) * _tmp10 - - P(11, 10) * _tmp11 - P(12, 10) * _tmp30 + P(2, 10) * _tmp8 + P(3, 10); - const Scalar _tmp55 = P(0, 2) * _tmp32 + P(1, 2) * _tmp43 + P(10, 2) * _tmp10 - - P(11, 2) * _tmp11 - P(12, 2) * _tmp30 + P(2, 2) * _tmp8 + P(3, 2); - const Scalar _tmp56 = P(0, 0) * _tmp32 + P(1, 0) * _tmp43 + P(10, 0) * _tmp10 - - P(12, 0) * _tmp30 + P(2, 0) * _tmp8 + P(3, 0) - _tmp23 * state(1, 0); - const Scalar _tmp57 = P(0, 1) * _tmp32 + P(1, 1) * _tmp43 + P(10, 1) * _tmp10 - - P(12, 1) * _tmp30 + P(2, 1) * _tmp8 + P(3, 1) - _tmp18 * state(1, 0); - const Scalar _tmp58 = P(0, 3) * _tmp32 + P(1, 3) * _tmp43 + P(10, 3) * _tmp10 - - P(11, 3) * _tmp11 - P(12, 3) * _tmp30 + P(2, 3) * _tmp8 + P(3, 3); - const Scalar _tmp59 = d_vel(1, 0) - state(14, 0); - const Scalar _tmp60 = 2 * state(2, 0); - const Scalar _tmp61 = _tmp59 * _tmp60; - const Scalar _tmp62 = d_vel(2, 0) - state(15, 0); - const Scalar _tmp63 = 2 * state(3, 0); - const Scalar _tmp64 = _tmp62 * _tmp63; - const Scalar _tmp65 = _tmp61 + _tmp64; - const Scalar _tmp66 = _tmp60 * _tmp62; - const Scalar _tmp67 = _tmp59 * _tmp63; - const Scalar _tmp68 = _tmp66 - _tmp67; - const Scalar _tmp69 = 2 * state(1, 0); - const Scalar _tmp70 = _tmp62 * _tmp69; - const Scalar _tmp71 = 2 * state(0, 0); - const Scalar _tmp72 = _tmp59 * _tmp71; - const Scalar _tmp73 = d_vel(0, 0) - state(13, 0); - const Scalar _tmp74 = 4 * state(3, 0); - const Scalar _tmp75 = _tmp70 - _tmp72 - _tmp73 * _tmp74; - const Scalar _tmp76 = _tmp71 * state(2, 0); - const Scalar _tmp77 = _tmp69 * state(3, 0); - const Scalar _tmp78 = _tmp76 + _tmp77; - const Scalar _tmp79 = P(0, 15) + P(1, 15) * _tmp8 + P(10, 15) * _tmp11 + P(11, 15) * _tmp10 + - P(12, 15) * _tmp9 + P(2, 15) * _tmp5 + P(3, 15) * _tmp2; - const Scalar _tmp80 = _tmp71 * state(3, 0); - const Scalar _tmp81 = _tmp69 * state(2, 0); - const Scalar _tmp82 = -_tmp80 + _tmp81; - const Scalar _tmp83 = P(0, 14) + P(1, 14) * _tmp8 + P(10, 14) * _tmp11 + P(11, 14) * _tmp10 + - P(12, 14) * _tmp9 + P(2, 14) * _tmp5 + P(3, 14) * _tmp2; - const Scalar _tmp84 = -2 * _tmp20; - const Scalar _tmp85 = -2 * _tmp25; - const Scalar _tmp86 = _tmp84 + _tmp85 + 1; - const Scalar _tmp87 = P(0, 13) + P(1, 13) * _tmp8 + P(10, 13) * _tmp11 + P(11, 13) * _tmp10 + - P(12, 13) * _tmp9 + P(2, 13) * _tmp5 + P(3, 13) * _tmp2; - const Scalar _tmp88 = _tmp59 * _tmp69; - const Scalar _tmp89 = _tmp62 * _tmp71; - const Scalar _tmp90 = 4 * state(2, 0); - const Scalar _tmp91 = -_tmp73 * _tmp90 + _tmp88 + _tmp89; - const Scalar _tmp92 = Scalar(0.5) * P(11, 4); - const Scalar _tmp93 = P(0, 4) + P(1, 4) * _tmp8 + P(10, 4) * _tmp11 + P(12, 4) * _tmp9 + - P(2, 4) * _tmp5 + P(3, 4) * _tmp2 + _tmp92 * state(2, 0); - const Scalar _tmp94 = P(0, 13) * _tmp33 + P(1, 13) - P(10, 13) * _tmp30 + P(11, 13) * _tmp9 - - P(12, 13) * _tmp10 + P(2, 13) * _tmp32 + P(3, 13) * _tmp5; - const Scalar _tmp95 = P(0, 15) * _tmp33 + P(1, 15) - P(10, 15) * _tmp30 + P(11, 15) * _tmp9 - - P(12, 15) * _tmp10 + P(2, 15) * _tmp32 + P(3, 15) * _tmp5; - const Scalar _tmp96 = P(0, 14) * _tmp33 + P(1, 14) - P(10, 14) * _tmp30 + P(11, 14) * _tmp9 - - P(12, 14) * _tmp10 + P(2, 14) * _tmp32 + P(3, 14) * _tmp5; - const Scalar _tmp97 = Scalar(0.5) * P(10, 4); - const Scalar _tmp98 = P(0, 4) * _tmp33 + P(1, 4) - P(12, 4) * _tmp10 + P(2, 4) * _tmp32 + - P(3, 4) * _tmp5 + _tmp92 * state(3, 0) - _tmp97 * state(0, 0); - const Scalar _tmp99 = P(0, 15) * _tmp43 + P(1, 15) * _tmp2 - P(10, 15) * _tmp9 - - P(11, 15) * _tmp30 + P(12, 15) * _tmp11 + P(2, 15) + P(3, 15) * _tmp33; - const Scalar _tmp100 = P(0, 14) * _tmp43 + P(1, 14) * _tmp2 - P(10, 14) * _tmp9 - - P(11, 14) * _tmp30 + P(12, 14) * _tmp11 + P(2, 14) + P(3, 14) * _tmp33; - const Scalar _tmp101 = P(0, 13) * _tmp43 + P(1, 13) * _tmp2 - P(10, 13) * _tmp9 - - P(11, 13) * _tmp30 + P(12, 13) * _tmp11 + P(2, 13) + P(3, 13) * _tmp33; - const Scalar _tmp102 = P(0, 4) * _tmp43 + P(1, 4) * _tmp2 - P(10, 4) * _tmp9 + P(12, 4) * _tmp11 + - P(2, 4) + P(3, 4) * _tmp33 - _tmp92 * state(0, 0); - const Scalar _tmp103 = P(0, 13) * _tmp32 + P(1, 13) * _tmp43 + P(10, 13) * _tmp10 - - P(11, 13) * _tmp11 - P(12, 13) * _tmp30 + P(2, 13) * _tmp8 + P(3, 13); - const Scalar _tmp104 = P(0, 14) * _tmp32 + P(1, 14) * _tmp43 + P(10, 14) * _tmp10 - - P(11, 14) * _tmp11 - P(12, 14) * _tmp30 + P(2, 14) * _tmp8 + P(3, 14); - const Scalar _tmp105 = P(0, 15) * _tmp32 + P(1, 15) * _tmp43 + P(10, 15) * _tmp10 - - P(11, 15) * _tmp11 - P(12, 15) * _tmp30 + P(2, 15) * _tmp8 + P(3, 15); - const Scalar _tmp106 = P(0, 4) * _tmp32 + P(1, 4) * _tmp43 - P(12, 4) * _tmp30 + P(2, 4) * _tmp8 + - P(3, 4) - _tmp92 * state(1, 0) + _tmp97 * state(2, 0); - const Scalar _tmp107 = P(0, 13) * _tmp68 + P(1, 13) * _tmp65 - P(13, 13) * _tmp86 - - P(14, 13) * _tmp82 - P(15, 13) * _tmp78 + P(2, 13) * _tmp91 + - P(3, 13) * _tmp75 + P(4, 13); - const Scalar _tmp108 = P(0, 14) * _tmp68 + P(1, 14) * _tmp65 - P(13, 14) * _tmp86 - - P(14, 14) * _tmp82 - P(15, 14) * _tmp78 + P(2, 14) * _tmp91 + - P(3, 14) * _tmp75 + P(4, 14); - const Scalar _tmp109 = P(0, 15) * _tmp68 + P(1, 15) * _tmp65 - P(13, 15) * _tmp86 - - P(14, 15) * _tmp82 - P(15, 15) * _tmp78 + P(2, 15) * _tmp91 + - P(3, 15) * _tmp75 + P(4, 15); - const Scalar _tmp110 = P(0, 0) * _tmp68 + P(1, 0) * _tmp65 - P(13, 0) * _tmp86 - - P(14, 0) * _tmp82 - P(15, 0) * _tmp78 + P(2, 0) * _tmp91 + - P(3, 0) * _tmp75 + P(4, 0); - const Scalar _tmp111 = P(0, 1) * _tmp68 + P(1, 1) * _tmp65 - P(13, 1) * _tmp86 - - P(14, 1) * _tmp82 - P(15, 1) * _tmp78 + P(2, 1) * _tmp91 + - P(3, 1) * _tmp75 + P(4, 1); - const Scalar _tmp112 = P(0, 2) * _tmp68 + P(1, 2) * _tmp65 - P(13, 2) * _tmp86 - - P(14, 2) * _tmp82 - P(15, 2) * _tmp78 + P(2, 2) * _tmp91 + - P(3, 2) * _tmp75 + P(4, 2); - const Scalar _tmp113 = P(0, 3) * _tmp68 + P(1, 3) * _tmp65 - P(13, 3) * _tmp86 - - P(14, 3) * _tmp82 - P(15, 3) * _tmp78 + P(2, 3) * _tmp91 + - P(3, 3) * _tmp75 + P(4, 3); - const Scalar _tmp114 = P(0, 4) * _tmp68 + P(1, 4) * _tmp65 - P(13, 4) * _tmp86 - - P(14, 4) * _tmp82 - P(15, 4) * _tmp78 + P(2, 4) * _tmp91 + - P(3, 4) * _tmp75 + P(4, 4); - const Scalar _tmp115 = _tmp69 * _tmp73; - const Scalar _tmp116 = _tmp115 + _tmp64; - const Scalar _tmp117 = _tmp63 * _tmp73; - const Scalar _tmp118 = _tmp117 - _tmp70; - const Scalar _tmp119 = _tmp71 * _tmp73; - const Scalar _tmp120 = _tmp119 - _tmp59 * _tmp74 + _tmp66; - const Scalar _tmp121 = _tmp80 + _tmp81; - const Scalar _tmp122 = _tmp60 * state(3, 0); - const Scalar _tmp123 = _tmp69 * state(0, 0); - const Scalar _tmp124 = _tmp122 - _tmp123; - const Scalar _tmp125 = 1 - 2 * _tmp27; - const Scalar _tmp126 = _tmp125 + _tmp84; - const Scalar _tmp127 = 4 * state(1, 0); - const Scalar _tmp128 = _tmp60 * _tmp73; - const Scalar _tmp129 = -_tmp127 * _tmp59 + _tmp128 - _tmp89; - const Scalar _tmp130 = Scalar(0.5) * P(11, 5); - const Scalar _tmp131 = P(0, 5) + P(1, 5) * _tmp8 + P(10, 5) * _tmp11 + P(12, 5) * _tmp9 + - P(2, 5) * _tmp5 + P(3, 5) * _tmp2 + _tmp130 * state(2, 0); - const Scalar _tmp132 = P(0, 5) * _tmp33 + P(1, 5) - P(10, 5) * _tmp30 - P(12, 5) * _tmp10 + - P(2, 5) * _tmp32 + P(3, 5) * _tmp5 + _tmp130 * state(3, 0); - const Scalar _tmp133 = P(0, 5) * _tmp43 + P(1, 5) * _tmp2 - P(10, 5) * _tmp9 + P(12, 5) * _tmp11 + - P(2, 5) + P(3, 5) * _tmp33 - _tmp130 * state(0, 0); - const Scalar _tmp134 = P(0, 5) * _tmp32 + P(1, 5) * _tmp43 + P(10, 5) * _tmp10 - - P(12, 5) * _tmp30 + P(2, 5) * _tmp8 + P(3, 5) - _tmp130 * state(1, 0); - const Scalar _tmp135 = _tmp86 * d_vel_var(0, 0); - const Scalar _tmp136 = _tmp82 * d_vel_var(1, 0); - const Scalar _tmp137 = _tmp78 * d_vel_var(2, 0); - const Scalar _tmp138 = P(0, 5) * _tmp68 + P(1, 5) * _tmp65 - P(13, 5) * _tmp86 - - P(14, 5) * _tmp82 - P(15, 5) * _tmp78 + P(2, 5) * _tmp91 + - P(3, 5) * _tmp75 + P(4, 5); - const Scalar _tmp139 = P(0, 1) * _tmp118 + P(1, 1) * _tmp129 - P(13, 1) * _tmp121 - - P(14, 1) * _tmp126 - P(15, 1) * _tmp124 + P(2, 1) * _tmp116 + - P(3, 1) * _tmp120 + P(5, 1); - const Scalar _tmp140 = P(0, 3) * _tmp118 + P(1, 3) * _tmp129 - P(13, 3) * _tmp121 - - P(14, 3) * _tmp126 - P(15, 3) * _tmp124 + P(2, 3) * _tmp116 + - P(3, 3) * _tmp120 + P(5, 3); - const Scalar _tmp141 = P(0, 13) * _tmp118 + P(1, 13) * _tmp129 - P(13, 13) * _tmp121 - - P(14, 13) * _tmp126 - P(15, 13) * _tmp124 + P(2, 13) * _tmp116 + - P(3, 13) * _tmp120 + P(5, 13); - const Scalar _tmp142 = P(0, 15) * _tmp118 + P(1, 15) * _tmp129 - P(13, 15) * _tmp121 - - P(14, 15) * _tmp126 - P(15, 15) * _tmp124 + P(2, 15) * _tmp116 + - P(3, 15) * _tmp120 + P(5, 15); - const Scalar _tmp143 = P(0, 14) * _tmp118 + P(1, 14) * _tmp129 - P(13, 14) * _tmp121 - - P(14, 14) * _tmp126 - P(15, 14) * _tmp124 + P(2, 14) * _tmp116 + - P(3, 14) * _tmp120 + P(5, 14); - const Scalar _tmp144 = P(0, 0) * _tmp118 + P(1, 0) * _tmp129 - P(13, 0) * _tmp121 - - P(14, 0) * _tmp126 - P(15, 0) * _tmp124 + P(2, 0) * _tmp116 + - P(3, 0) * _tmp120 + P(5, 0); - const Scalar _tmp145 = P(0, 2) * _tmp118 + P(1, 2) * _tmp129 - P(13, 2) * _tmp121 - - P(14, 2) * _tmp126 - P(15, 2) * _tmp124 + P(2, 2) * _tmp116 + - P(3, 2) * _tmp120 + P(5, 2); - const Scalar _tmp146 = P(0, 5) * _tmp118 + P(1, 5) * _tmp129 - P(13, 5) * _tmp121 - - P(14, 5) * _tmp126 - P(15, 5) * _tmp124 + P(2, 5) * _tmp116 + - P(3, 5) * _tmp120 + P(5, 5); - const Scalar _tmp147 = _tmp115 + _tmp61; - const Scalar _tmp148 = -_tmp128 + _tmp88; - const Scalar _tmp149 = -_tmp119 - _tmp62 * _tmp90 + _tmp67; - const Scalar _tmp150 = _tmp117 - _tmp127 * _tmp62 + _tmp72; - const Scalar _tmp151 = -_tmp76 + _tmp77; - const Scalar _tmp152 = _tmp122 + _tmp123; - const Scalar _tmp153 = _tmp125 + _tmp85; - const Scalar _tmp154 = Scalar(0.5) * P(11, 6); - const Scalar _tmp155 = P(0, 6) + P(1, 6) * _tmp8 + P(10, 6) * _tmp11 + P(12, 6) * _tmp9 + - P(2, 6) * _tmp5 + P(3, 6) * _tmp2 + _tmp154 * state(2, 0); - const Scalar _tmp156 = P(0, 6) * _tmp33 + P(1, 6) - P(10, 6) * _tmp30 - P(12, 6) * _tmp10 + - P(2, 6) * _tmp32 + P(3, 6) * _tmp5 + _tmp154 * state(3, 0); - const Scalar _tmp157 = P(0, 6) * _tmp43 + P(1, 6) * _tmp2 - P(10, 6) * _tmp9 + P(12, 6) * _tmp11 + - P(2, 6) + P(3, 6) * _tmp33 - _tmp154 * state(0, 0); - const Scalar _tmp158 = P(0, 6) * _tmp32 + P(1, 6) * _tmp43 + P(10, 6) * _tmp10 - - P(12, 6) * _tmp30 + P(2, 6) * _tmp8 + P(3, 6) - _tmp154 * state(1, 0); - const Scalar _tmp159 = P(0, 6) * _tmp68 + P(1, 6) * _tmp65 - P(13, 6) * _tmp86 - - P(14, 6) * _tmp82 - P(15, 6) * _tmp78 + P(2, 6) * _tmp91 + - P(3, 6) * _tmp75 + P(4, 6); - const Scalar _tmp160 = P(0, 6) * _tmp118 + P(1, 6) * _tmp129 - P(13, 6) * _tmp121 - - P(14, 6) * _tmp126 - P(15, 6) * _tmp124 + P(2, 6) * _tmp116 + - P(3, 6) * _tmp120 + P(5, 6); - const Scalar _tmp161 = P(0, 13) * _tmp148 + P(1, 13) * _tmp150 - P(13, 13) * _tmp151 - - P(14, 13) * _tmp152 - P(15, 13) * _tmp153 + P(2, 13) * _tmp149 + - P(3, 13) * _tmp147 + P(6, 13); - const Scalar _tmp162 = P(0, 14) * _tmp148 + P(1, 14) * _tmp150 - P(13, 14) * _tmp151 - - P(14, 14) * _tmp152 - P(15, 14) * _tmp153 + P(2, 14) * _tmp149 + - P(3, 14) * _tmp147 + P(6, 14); - const Scalar _tmp163 = P(0, 15) * _tmp148 + P(1, 15) * _tmp150 - P(13, 15) * _tmp151 - - P(14, 15) * _tmp152 - P(15, 15) * _tmp153 + P(2, 15) * _tmp149 + - P(3, 15) * _tmp147 + P(6, 15); - const Scalar _tmp164 = P(0, 6) * _tmp148 + P(1, 6) * _tmp150 - P(13, 6) * _tmp151 - - P(14, 6) * _tmp152 - P(15, 6) * _tmp153 + P(2, 6) * _tmp149 + - P(3, 6) * _tmp147 + P(6, 6); - const Scalar _tmp165 = Scalar(0.5) * P(12, 7); - const Scalar _tmp166 = Scalar(0.5) * P(11, 8); - const Scalar _tmp167 = Scalar(0.5) * P(12, 8); - const Scalar _tmp168 = Scalar(0.5) * P(11, 9); - const Scalar _tmp169 = Scalar(0.5) * P(10, 9); - const Scalar _tmp170 = Scalar(0.5) * P(12, 9); + const Scalar _tmp26 = _tmp20 * _tmp25; + const Scalar _tmp27 = _tmp24 + _tmp26; + const Scalar _tmp28 = _tmp20 * state(1, 0); + const Scalar _tmp29 = _tmp1 * state(0, 0); + const Scalar _tmp30 = _tmp0 - _tmp2; + const Scalar _tmp31 = _tmp4 - _tmp5; + const Scalar _tmp32 = P(0, 10) * _tmp30 + P(1, 10) - P(10, 10) * _tmp29 + P(11, 10) * _tmp11 - + P(12, 10) * _tmp10 + P(2, 10) * _tmp31 + P(3, 10) * _tmp9; + const Scalar _tmp33 = P(0, 11) * _tmp30 + P(1, 11) - P(10, 11) * _tmp29 + P(11, 11) * _tmp11 - + P(12, 11) * _tmp10 + P(2, 11) * _tmp31 + P(3, 11) * _tmp9; + const Scalar _tmp34 = P(0, 12) * _tmp30 + P(1, 12) - P(10, 12) * _tmp29 + P(11, 12) * _tmp11 - + P(12, 12) * _tmp10 + P(2, 12) * _tmp31 + P(3, 12) * _tmp9; + const Scalar _tmp35 = P(0, 0) * _tmp30 + P(1, 0) - P(10, 0) * _tmp29 + P(11, 0) * _tmp11 - + P(12, 0) * _tmp10 + P(2, 0) * _tmp31 + P(3, 0) * _tmp9; + const Scalar _tmp36 = P(0, 3) * _tmp30 + P(1, 3) - P(10, 3) * _tmp29 + P(11, 3) * _tmp11 - + P(12, 3) * _tmp10 + P(2, 3) * _tmp31 + P(3, 3) * _tmp9; + const Scalar _tmp37 = P(0, 2) * _tmp30 + P(1, 2) - P(10, 2) * _tmp29 + P(11, 2) * _tmp11 - + P(12, 2) * _tmp10 + P(2, 2) * _tmp31 + P(3, 2) * _tmp9; + const Scalar _tmp38 = _tmp20 * std::pow(state(0, 0), Scalar(2)); + const Scalar _tmp39 = P(0, 1) * _tmp30 + P(1, 1) - P(10, 1) * _tmp29 + P(11, 1) * _tmp11 - + P(12, 1) * _tmp10 + P(2, 1) * _tmp31 + P(3, 1) * _tmp9; + const Scalar _tmp40 = _tmp20 * state(0, 0); + const Scalar _tmp41 = _tmp7 - _tmp8; + const Scalar _tmp42 = P(0, 11) * _tmp41 + P(1, 11) * _tmp6 - P(10, 11) * _tmp11 - + P(11, 11) * _tmp29 + P(12, 11) * _tmp12 + P(2, 11) + P(3, 11) * _tmp30; + const Scalar _tmp43 = P(0, 10) * _tmp41 + P(1, 10) * _tmp6 - P(10, 10) * _tmp11 - + P(11, 10) * _tmp29 + P(12, 10) * _tmp12 + P(2, 10) + P(3, 10) * _tmp30; + const Scalar _tmp44 = P(0, 12) * _tmp41 + P(1, 12) * _tmp6 - P(10, 12) * _tmp11 - + P(11, 12) * _tmp29 + P(12, 12) * _tmp12 + P(2, 12) + P(3, 12) * _tmp30; + const Scalar _tmp45 = P(0, 3) * _tmp41 + P(1, 3) * _tmp6 - P(10, 3) * _tmp11 - P(11, 3) * _tmp29 + + P(12, 3) * _tmp12 + P(2, 3) + P(3, 3) * _tmp30; + const Scalar _tmp46 = P(0, 1) * _tmp41 + P(1, 1) * _tmp6 - P(10, 1) * _tmp11 - P(11, 1) * _tmp29 + + P(12, 1) * _tmp12 + P(2, 1) + P(3, 1) * _tmp30; + const Scalar _tmp47 = P(0, 0) * _tmp41 + P(1, 0) * _tmp6 - P(10, 0) * _tmp11 - P(11, 0) * _tmp29 + + P(12, 0) * _tmp12 + P(2, 0) + P(3, 0) * _tmp30; + const Scalar _tmp48 = P(0, 2) * _tmp41 + P(1, 2) * _tmp6 - P(10, 2) * _tmp11 - P(11, 2) * _tmp29 + + P(12, 2) * _tmp12 + P(2, 2) + P(3, 2) * _tmp30; + const Scalar _tmp49 = _tmp21 + _tmp38; + const Scalar _tmp50 = P(0, 10) * _tmp31 + P(1, 10) * _tmp41 + P(10, 10) * _tmp10 - + P(11, 10) * _tmp12 - P(12, 10) * _tmp29 + P(2, 10) * _tmp3 + P(3, 10); + const Scalar _tmp51 = P(0, 11) * _tmp31 + P(1, 11) * _tmp41 + P(10, 11) * _tmp10 - + P(11, 11) * _tmp12 - P(12, 11) * _tmp29 + P(2, 11) * _tmp3 + P(3, 11); + const Scalar _tmp52 = P(0, 12) * _tmp31 + P(1, 12) * _tmp41 + P(10, 12) * _tmp10 - + P(11, 12) * _tmp12 - P(12, 12) * _tmp29 + P(2, 12) * _tmp3 + P(3, 12); + const Scalar _tmp53 = P(0, 2) * _tmp31 + P(1, 2) * _tmp41 + P(10, 2) * _tmp10 - + P(11, 2) * _tmp12 - P(12, 2) * _tmp29 + P(2, 2) * _tmp3 + P(3, 2); + const Scalar _tmp54 = P(0, 1) * _tmp31 + P(1, 1) * _tmp41 + P(10, 1) * _tmp10 - + P(11, 1) * _tmp12 - P(12, 1) * _tmp29 + P(2, 1) * _tmp3 + P(3, 1); + const Scalar _tmp55 = P(0, 0) * _tmp31 + P(1, 0) * _tmp41 + P(10, 0) * _tmp10 - + P(11, 0) * _tmp12 - P(12, 0) * _tmp29 + P(2, 0) * _tmp3 + P(3, 0); + const Scalar _tmp56 = P(0, 3) * _tmp31 + P(1, 3) * _tmp41 + P(10, 3) * _tmp10 - + P(11, 3) * _tmp12 - P(12, 3) * _tmp29 + P(2, 3) * _tmp3 + P(3, 3); + const Scalar _tmp57 = P(0, 13) + P(1, 13) * _tmp3 + P(10, 13) * _tmp12 + P(11, 13) * _tmp10 + + P(12, 13) * _tmp11 + P(2, 13) * _tmp9 + P(3, 13) * _tmp6; + const Scalar _tmp58 = -2 * _tmp23; + const Scalar _tmp59 = 1 - 2 * _tmp25; + const Scalar _tmp60 = _tmp58 + _tmp59; + const Scalar _tmp61 = _tmp60 * dt; + const Scalar _tmp62 = P(0, 15) + P(1, 15) * _tmp3 + P(10, 15) * _tmp12 + P(11, 15) * _tmp10 + + P(12, 15) * _tmp11 + P(2, 15) * _tmp9 + P(3, 15) * _tmp6; + const Scalar _tmp63 = 2 * state(0, 0); + const Scalar _tmp64 = _tmp63 * state(2, 0); + const Scalar _tmp65 = 2 * state(1, 0); + const Scalar _tmp66 = _tmp65 * state(3, 0); + const Scalar _tmp67 = _tmp64 + _tmp66; + const Scalar _tmp68 = _tmp67 * dt; + const Scalar _tmp69 = P(0, 14) + P(1, 14) * _tmp3 + P(10, 14) * _tmp12 + P(11, 14) * _tmp10 + + P(12, 14) * _tmp11 + P(2, 14) * _tmp9 + P(3, 14) * _tmp6; + const Scalar _tmp70 = _tmp63 * state(3, 0); + const Scalar _tmp71 = _tmp65 * state(2, 0); + const Scalar _tmp72 = -_tmp70 + _tmp71; + const Scalar _tmp73 = _tmp72 * dt; + const Scalar _tmp74 = d_vel(1, 0) - dt * state(14, 0); + const Scalar _tmp75 = 2 * state(3, 0); + const Scalar _tmp76 = _tmp74 * _tmp75; + const Scalar _tmp77 = d_vel(2, 0) - dt * state(15, 0); + const Scalar _tmp78 = 2 * state(2, 0); + const Scalar _tmp79 = _tmp77 * _tmp78; + const Scalar _tmp80 = -_tmp76 + _tmp79; + const Scalar _tmp81 = _tmp74 * _tmp78; + const Scalar _tmp82 = _tmp75 * _tmp77; + const Scalar _tmp83 = _tmp81 + _tmp82; + const Scalar _tmp84 = _tmp63 * _tmp74; + const Scalar _tmp85 = d_vel(0, 0) - dt * state(13, 0); + const Scalar _tmp86 = 4 * _tmp85; + const Scalar _tmp87 = _tmp65 * _tmp77; + const Scalar _tmp88 = -_tmp84 - _tmp86 * state(3, 0) + _tmp87; + const Scalar _tmp89 = _tmp65 * _tmp74; + const Scalar _tmp90 = _tmp63 * _tmp77; + const Scalar _tmp91 = -_tmp86 * state(2, 0) + _tmp89 + _tmp90; + const Scalar _tmp92 = P(0, 4) + P(1, 4) * _tmp3 + P(10, 4) * _tmp12 + P(11, 4) * _tmp10 + + P(12, 4) * _tmp11 + P(2, 4) * _tmp9 + P(3, 4) * _tmp6; + const Scalar _tmp93 = P(0, 13) * _tmp30 + P(1, 13) - P(10, 13) * _tmp29 + P(11, 13) * _tmp11 - + P(12, 13) * _tmp10 + P(2, 13) * _tmp31 + P(3, 13) * _tmp9; + const Scalar _tmp94 = P(0, 15) * _tmp30 + P(1, 15) - P(10, 15) * _tmp29 + P(11, 15) * _tmp11 - + P(12, 15) * _tmp10 + P(2, 15) * _tmp31 + P(3, 15) * _tmp9; + const Scalar _tmp95 = P(0, 14) * _tmp30 + P(1, 14) - P(10, 14) * _tmp29 + P(11, 14) * _tmp11 - + P(12, 14) * _tmp10 + P(2, 14) * _tmp31 + P(3, 14) * _tmp9; + const Scalar _tmp96 = P(0, 4) * _tmp30 + P(1, 4) - P(10, 4) * _tmp29 + P(11, 4) * _tmp11 - + P(12, 4) * _tmp10 + P(2, 4) * _tmp31 + P(3, 4) * _tmp9; + const Scalar _tmp97 = P(0, 15) * _tmp41 + P(1, 15) * _tmp6 - P(10, 15) * _tmp11 - + P(11, 15) * _tmp29 + P(12, 15) * _tmp12 + P(2, 15) + P(3, 15) * _tmp30; + const Scalar _tmp98 = P(0, 14) * _tmp41 + P(1, 14) * _tmp6 - P(10, 14) * _tmp11 - + P(11, 14) * _tmp29 + P(12, 14) * _tmp12 + P(2, 14) + P(3, 14) * _tmp30; + const Scalar _tmp99 = _tmp98 * dt; + const Scalar _tmp100 = P(0, 13) * _tmp41 + P(1, 13) * _tmp6 - P(10, 13) * _tmp11 - + P(11, 13) * _tmp29 + P(12, 13) * _tmp12 + P(2, 13) + P(3, 13) * _tmp30; + const Scalar _tmp101 = _tmp100 * dt; + const Scalar _tmp102 = P(0, 4) * _tmp41 + P(1, 4) * _tmp6 - P(10, 4) * _tmp11 - + P(11, 4) * _tmp29 + P(12, 4) * _tmp12 + P(2, 4) + P(3, 4) * _tmp30; + const Scalar _tmp103 = P(0, 15) * _tmp31 + P(1, 15) * _tmp41 + P(10, 15) * _tmp10 - + P(11, 15) * _tmp12 - P(12, 15) * _tmp29 + P(2, 15) * _tmp3 + P(3, 15); + const Scalar _tmp104 = P(0, 14) * _tmp31 + P(1, 14) * _tmp41 + P(10, 14) * _tmp10 - + P(11, 14) * _tmp12 - P(12, 14) * _tmp29 + P(2, 14) * _tmp3 + P(3, 14); + const Scalar _tmp105 = P(0, 13) * _tmp31 + P(1, 13) * _tmp41 + P(10, 13) * _tmp10 - + P(11, 13) * _tmp12 - P(12, 13) * _tmp29 + P(2, 13) * _tmp3 + P(3, 13); + const Scalar _tmp106 = P(0, 4) * _tmp31 + P(1, 4) * _tmp41 + P(10, 4) * _tmp10 - + P(11, 4) * _tmp12 - P(12, 4) * _tmp29 + P(2, 4) * _tmp3 + P(3, 4); + const Scalar _tmp107 = P(0, 1) * _tmp80 + P(1, 1) * _tmp83 - P(13, 1) * _tmp61 - + P(14, 1) * _tmp73 - P(15, 1) * _tmp68 + P(2, 1) * _tmp91 + + P(3, 1) * _tmp88 + P(4, 1); + const Scalar _tmp108 = P(0, 0) * _tmp80 + P(1, 0) * _tmp83 - P(13, 0) * _tmp61 - + P(14, 0) * _tmp73 - P(15, 0) * _tmp68 + P(2, 0) * _tmp91 + + P(3, 0) * _tmp88 + P(4, 0); + const Scalar _tmp109 = P(0, 13) * _tmp80 + P(1, 13) * _tmp83 - P(13, 13) * _tmp61 - + P(14, 13) * _tmp73 - P(15, 13) * _tmp68 + P(2, 13) * _tmp91 + + P(3, 13) * _tmp88 + P(4, 13); + const Scalar _tmp110 = P(0, 15) * _tmp80 + P(1, 15) * _tmp83 - P(13, 15) * _tmp61 - + P(14, 15) * _tmp73 - P(15, 15) * _tmp68 + P(2, 15) * _tmp91 + + P(3, 15) * _tmp88 + P(4, 15); + const Scalar _tmp111 = P(0, 14) * _tmp80 + P(1, 14) * _tmp83 - P(13, 14) * _tmp61 - + P(14, 14) * _tmp73 - P(15, 14) * _tmp68 + P(2, 14) * _tmp91 + + P(3, 14) * _tmp88 + P(4, 14); + const Scalar _tmp112 = P(0, 3) * _tmp80 + P(1, 3) * _tmp83 - P(13, 3) * _tmp61 - + P(14, 3) * _tmp73 - P(15, 3) * _tmp68 + P(2, 3) * _tmp91 + + P(3, 3) * _tmp88 + P(4, 3); + const Scalar _tmp113 = P(0, 2) * _tmp80 + P(1, 2) * _tmp83 - P(13, 2) * _tmp61 - + P(14, 2) * _tmp73 - P(15, 2) * _tmp68 + P(2, 2) * _tmp91 + + P(3, 2) * _tmp88 + P(4, 2); + const Scalar _tmp114 = P(0, 4) * _tmp80 + P(1, 4) * _tmp83 - P(13, 4) * _tmp61 - + P(14, 4) * _tmp73 - P(15, 4) * _tmp68 + P(2, 4) * _tmp91 + + P(3, 4) * _tmp88 + P(4, 4); + const Scalar _tmp115 = -2 * _tmp19; + const Scalar _tmp116 = _tmp115 + _tmp58 + 1; + const Scalar _tmp117 = _tmp116 * dt; + const Scalar _tmp118 = _tmp70 + _tmp71; + const Scalar _tmp119 = _tmp118 * dt; + const Scalar _tmp120 = _tmp65 * _tmp85; + const Scalar _tmp121 = _tmp120 + _tmp82; + const Scalar _tmp122 = _tmp75 * _tmp85; + const Scalar _tmp123 = _tmp122 - _tmp87; + const Scalar _tmp124 = 4 * _tmp74; + const Scalar _tmp125 = _tmp78 * _tmp85; + const Scalar _tmp126 = -_tmp124 * state(1, 0) + _tmp125 - _tmp90; + const Scalar _tmp127 = _tmp63 * _tmp85; + const Scalar _tmp128 = -_tmp124 * state(3, 0) + _tmp127 + _tmp79; + const Scalar _tmp129 = _tmp75 * state(2, 0); + const Scalar _tmp130 = _tmp63 * state(1, 0); + const Scalar _tmp131 = _tmp129 - _tmp130; + const Scalar _tmp132 = _tmp131 * dt; + const Scalar _tmp133 = P(0, 5) + P(1, 5) * _tmp3 + P(10, 5) * _tmp12 + P(11, 5) * _tmp10 + + P(12, 5) * _tmp11 + P(2, 5) * _tmp9 + P(3, 5) * _tmp6; + const Scalar _tmp134 = P(0, 5) * _tmp30 + P(1, 5) - P(10, 5) * _tmp29 + P(11, 5) * _tmp11 - + P(12, 5) * _tmp10 + P(2, 5) * _tmp31 + P(3, 5) * _tmp9; + const Scalar _tmp135 = P(0, 5) * _tmp41 + P(1, 5) * _tmp6 - P(10, 5) * _tmp11 - + P(11, 5) * _tmp29 + P(12, 5) * _tmp12 + P(2, 5) + P(3, 5) * _tmp30; + const Scalar _tmp136 = P(0, 5) * _tmp31 + P(1, 5) * _tmp41 + P(10, 5) * _tmp10 - + P(11, 5) * _tmp12 - P(12, 5) * _tmp29 + P(2, 5) * _tmp3 + P(3, 5); + const Scalar _tmp137 = _tmp118 * d_vel_var(0, 0); + const Scalar _tmp138 = _tmp72 * d_vel_var(1, 0); + const Scalar _tmp139 = _tmp67 * d_vel_var(2, 0); + const Scalar _tmp140 = P(0, 5) * _tmp80 + P(1, 5) * _tmp83 - P(13, 5) * _tmp61 - + P(14, 5) * _tmp73 - P(15, 5) * _tmp68 + P(2, 5) * _tmp91 + + P(3, 5) * _tmp88 + P(4, 5); + const Scalar _tmp141 = P(0, 0) * _tmp123 + P(1, 0) * _tmp126 - P(13, 0) * _tmp119 - + P(14, 0) * _tmp117 - P(15, 0) * _tmp132 + P(2, 0) * _tmp121 + + P(3, 0) * _tmp128 + P(5, 0); + const Scalar _tmp142 = P(0, 2) * _tmp123 + P(1, 2) * _tmp126 - P(13, 2) * _tmp119 - + P(14, 2) * _tmp117 - P(15, 2) * _tmp132 + P(2, 2) * _tmp121 + + P(3, 2) * _tmp128 + P(5, 2); + const Scalar _tmp143 = P(0, 14) * _tmp123 + P(1, 14) * _tmp126 - P(13, 14) * _tmp119 - + P(14, 14) * _tmp117 - P(15, 14) * _tmp132 + P(2, 14) * _tmp121 + + P(3, 14) * _tmp128 + P(5, 14); + const Scalar _tmp144 = P(0, 15) * _tmp123 + P(1, 15) * _tmp126 - P(13, 15) * _tmp119 - + P(14, 15) * _tmp117 - P(15, 15) * _tmp132 + P(2, 15) * _tmp121 + + P(3, 15) * _tmp128 + P(5, 15); + const Scalar _tmp145 = P(0, 3) * _tmp123 + P(1, 3) * _tmp126 - P(13, 3) * _tmp119 - + P(14, 3) * _tmp117 - P(15, 3) * _tmp132 + P(2, 3) * _tmp121 + + P(3, 3) * _tmp128 + P(5, 3); + const Scalar _tmp146 = P(0, 1) * _tmp123 + P(1, 1) * _tmp126 - P(13, 1) * _tmp119 - + P(14, 1) * _tmp117 - P(15, 1) * _tmp132 + P(2, 1) * _tmp121 + + P(3, 1) * _tmp128 + P(5, 1); + const Scalar _tmp147 = P(0, 13) * _tmp123 + P(1, 13) * _tmp126 - P(13, 13) * _tmp119 - + P(14, 13) * _tmp117 - P(15, 13) * _tmp132 + P(2, 13) * _tmp121 + + P(3, 13) * _tmp128 + P(5, 13); + const Scalar _tmp148 = _tmp147 * dt; + const Scalar _tmp149 = P(0, 5) * _tmp123 + P(1, 5) * _tmp126 - P(13, 5) * _tmp119 - + P(14, 5) * _tmp117 - P(15, 5) * _tmp132 + P(2, 5) * _tmp121 + + P(3, 5) * _tmp128 + P(5, 5); + const Scalar _tmp150 = _tmp115 + _tmp59; + const Scalar _tmp151 = _tmp150 * dt; + const Scalar _tmp152 = -_tmp64 + _tmp66; + const Scalar _tmp153 = _tmp152 * dt; + const Scalar _tmp154 = -_tmp125 + _tmp89; + const Scalar _tmp155 = _tmp120 + _tmp81; + const Scalar _tmp156 = 4 * _tmp77; + const Scalar _tmp157 = _tmp122 - _tmp156 * state(1, 0) + _tmp84; + const Scalar _tmp158 = -_tmp127 - _tmp156 * state(2, 0) + _tmp76; + const Scalar _tmp159 = _tmp129 + _tmp130; + const Scalar _tmp160 = _tmp159 * dt; + const Scalar _tmp161 = P(11, 6) * _tmp1; + const Scalar _tmp162 = P(0, 6) + P(1, 6) * _tmp3 + P(10, 6) * _tmp12 + P(12, 6) * _tmp11 + + P(2, 6) * _tmp9 + P(3, 6) * _tmp6 + _tmp161 * state(2, 0); + const Scalar _tmp163 = P(0, 6) * _tmp30 + P(1, 6) - P(10, 6) * _tmp29 - P(12, 6) * _tmp10 + + P(2, 6) * _tmp31 + P(3, 6) * _tmp9 + _tmp161 * state(3, 0); + const Scalar _tmp164 = P(0, 6) * _tmp41 + P(1, 6) * _tmp6 - P(10, 6) * _tmp11 + + P(12, 6) * _tmp12 + P(2, 6) + P(3, 6) * _tmp30 - _tmp161 * state(0, 0); + const Scalar _tmp165 = P(0, 6) * _tmp31 + P(1, 6) * _tmp41 + P(10, 6) * _tmp10 - + P(11, 6) * _tmp12 - P(12, 6) * _tmp29 + P(2, 6) * _tmp3 + P(3, 6); + const Scalar _tmp166 = P(0, 6) * _tmp80 + P(1, 6) * _tmp83 - P(13, 6) * _tmp61 - + P(14, 6) * _tmp73 - P(15, 6) * _tmp68 + P(2, 6) * _tmp91 + + P(3, 6) * _tmp88 + P(4, 6); + const Scalar _tmp167 = P(0, 6) * _tmp123 + P(1, 6) * _tmp126 - P(13, 6) * _tmp119 - + P(14, 6) * _tmp117 - P(15, 6) * _tmp132 + P(2, 6) * _tmp121 + + P(3, 6) * _tmp128 + P(5, 6); + const Scalar _tmp168 = P(0, 13) * _tmp154 + P(1, 13) * _tmp157 - P(13, 13) * _tmp153 - + P(14, 13) * _tmp160 - P(15, 13) * _tmp151 + P(2, 13) * _tmp158 + + P(3, 13) * _tmp155 + P(6, 13); + const Scalar _tmp169 = P(0, 15) * _tmp154 + P(1, 15) * _tmp157 - P(13, 15) * _tmp153 - + P(14, 15) * _tmp160 - P(15, 15) * _tmp151 + P(2, 15) * _tmp158 + + P(3, 15) * _tmp155 + P(6, 15); + const Scalar _tmp170 = P(0, 14) * _tmp154 + P(1, 14) * _tmp157 - P(13, 14) * _tmp153 - + P(14, 14) * _tmp160 - P(15, 14) * _tmp151 + P(2, 14) * _tmp158 + + P(3, 14) * _tmp155 + P(6, 14); + const Scalar _tmp171 = P(0, 6) * _tmp154 + P(1, 6) * _tmp157 - P(13, 6) * _tmp153 - + P(14, 6) * _tmp160 - P(15, 6) * _tmp151 + P(2, 6) * _tmp158 + + P(3, 6) * _tmp155 + P(6, 6); + const Scalar _tmp172 = P(11, 8) * _tmp1; + const Scalar _tmp173 = P(11, 9) * _tmp1; // Output terms (1) if (P_new != nullptr) { matrix::Matrix& _p_new = (*P_new); - _p_new(0, 0) = _tmp10 * _tmp12 + _tmp11 * _tmp13 + _tmp14 * _tmp9 + _tmp15 * _tmp5 + - _tmp17 * _tmp2 + _tmp19 * _tmp8 + _tmp22 + _tmp24 + _tmp29; + _p_new(0, 0) = _tmp10 * _tmp14 + _tmp11 * _tmp13 + _tmp12 * _tmp15 + _tmp16 * _tmp9 + + _tmp17 * _tmp3 + _tmp18 * _tmp6 + _tmp21 + _tmp22 + _tmp27; _p_new(1, 0) = 0; _p_new(2, 0) = 0; _p_new(3, 0) = 0; @@ -338,10 +341,10 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 0) = 0; _p_new(22, 0) = 0; _p_new(23, 0) = 0; - _p_new(0, 1) = -_tmp10 * _tmp14 + _tmp12 * _tmp9 - _tmp13 * _tmp30 + _tmp15 * _tmp32 + - _tmp17 * _tmp5 + _tmp19 + _tmp24 * _tmp33 - _tmp31 * state(1, 0); - _p_new(1, 1) = -_tmp10 * _tmp34 + _tmp26 - _tmp30 * _tmp36 + _tmp32 * _tmp38 + _tmp33 * _tmp39 + - _tmp35 * _tmp9 + _tmp37 * _tmp5 + _tmp40 + _tmp42; + _p_new(0, 1) = -_tmp10 * _tmp13 + _tmp11 * _tmp14 - _tmp15 * _tmp29 + _tmp16 * _tmp31 + _tmp17 + + _tmp18 * _tmp9 + _tmp22 * _tmp30 - _tmp28 * state(0, 0); + _p_new(1, 1) = -_tmp10 * _tmp34 + _tmp11 * _tmp33 + _tmp27 - _tmp29 * _tmp32 + _tmp30 * _tmp35 + + _tmp31 * _tmp37 + _tmp36 * _tmp9 + _tmp38 + _tmp39; _p_new(2, 1) = 0; _p_new(3, 1) = 0; _p_new(4, 1) = 0; @@ -364,12 +367,12 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 1) = 0; _p_new(22, 1) = 0; _p_new(23, 1) = 0; - _p_new(0, 2) = _tmp11 * _tmp14 - _tmp12 * _tmp30 - _tmp13 * _tmp9 + _tmp15 + _tmp17 * _tmp33 + - _tmp19 * _tmp2 + _tmp24 * _tmp43 - _tmp31 * state(2, 0); - _p_new(1, 2) = _tmp11 * _tmp34 + _tmp2 * _tmp40 - _tmp21 * state(1, 0) * state(2, 0) - - _tmp30 * _tmp35 + _tmp33 * _tmp37 - _tmp36 * _tmp9 + _tmp38 + _tmp39 * _tmp43; - _p_new(2, 2) = _tmp11 * _tmp44 + _tmp2 * _tmp48 + _tmp28 - _tmp30 * _tmp45 + _tmp33 * _tmp49 + - _tmp42 + _tmp43 * _tmp47 - _tmp46 * _tmp9 + _tmp50; + _p_new(0, 2) = -_tmp11 * _tmp15 + _tmp12 * _tmp13 - _tmp14 * _tmp29 + _tmp16 + _tmp17 * _tmp6 + + _tmp18 * _tmp30 + _tmp22 * _tmp41 - _tmp40 * state(2, 0); + _p_new(1, 2) = -_tmp11 * _tmp32 + _tmp12 * _tmp34 - _tmp28 * state(2, 0) - _tmp29 * _tmp33 + + _tmp30 * _tmp36 + _tmp35 * _tmp41 + _tmp37 + _tmp39 * _tmp6; + _p_new(2, 2) = -_tmp11 * _tmp43 + _tmp12 * _tmp44 + _tmp24 - _tmp29 * _tmp42 + _tmp30 * _tmp45 + + _tmp41 * _tmp47 + _tmp46 * _tmp6 + _tmp48 + _tmp49; _p_new(3, 2) = 0; _p_new(4, 2) = 0; _p_new(5, 2) = 0; @@ -391,14 +394,14 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 2) = 0; _p_new(22, 2) = 0; _p_new(23, 2) = 0; - _p_new(0, 3) = _tmp10 * _tmp13 - _tmp11 * _tmp12 - _tmp14 * _tmp30 + _tmp15 * _tmp8 + _tmp17 + - _tmp19 * _tmp43 + _tmp24 * _tmp32 - _tmp51 * state(0, 0); - _p_new(1, 3) = _tmp10 * _tmp36 - _tmp11 * _tmp35 - _tmp30 * _tmp34 + _tmp32 * _tmp39 + _tmp37 + - _tmp38 * _tmp8 + _tmp40 * _tmp43 - _tmp51 * state(1, 0); - _p_new(2, 3) = _tmp10 * _tmp46 - _tmp11 * _tmp45 - _tmp30 * _tmp44 + _tmp32 * _tmp47 + - _tmp43 * _tmp48 + _tmp49 + _tmp50 * _tmp8 - _tmp51 * state(2, 0); - _p_new(3, 3) = _tmp10 * _tmp54 - _tmp11 * _tmp53 + _tmp29 - _tmp30 * _tmp52 + _tmp32 * _tmp56 + - _tmp41 + _tmp43 * _tmp57 + _tmp55 * _tmp8 + _tmp58; + _p_new(0, 3) = _tmp10 * _tmp15 - _tmp12 * _tmp14 - _tmp13 * _tmp29 + _tmp16 * _tmp3 + + _tmp17 * _tmp41 + _tmp18 + _tmp22 * _tmp31 - _tmp40 * state(3, 0); + _p_new(1, 3) = _tmp10 * _tmp32 - _tmp12 * _tmp33 - _tmp28 * state(3, 0) - _tmp29 * _tmp34 + + _tmp3 * _tmp37 + _tmp31 * _tmp35 + _tmp36 + _tmp39 * _tmp41; + _p_new(2, 3) = _tmp10 * _tmp43 - _tmp12 * _tmp42 - _tmp20 * state(2, 0) * state(3, 0) - + _tmp29 * _tmp44 + _tmp3 * _tmp48 + _tmp31 * _tmp47 + _tmp41 * _tmp46 + _tmp45; + _p_new(3, 3) = _tmp10 * _tmp50 - _tmp12 * _tmp51 + _tmp26 - _tmp29 * _tmp52 + _tmp3 * _tmp53 + + _tmp31 * _tmp55 + _tmp41 * _tmp54 + _tmp49 + _tmp56; _p_new(4, 3) = 0; _p_new(5, 3) = 0; _p_new(6, 3) = 0; @@ -419,19 +422,19 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 3) = 0; _p_new(22, 3) = 0; _p_new(23, 3) = 0; - _p_new(0, 4) = _tmp15 * _tmp91 + _tmp17 * _tmp75 + _tmp19 * _tmp65 + _tmp24 * _tmp68 - - _tmp78 * _tmp79 - _tmp82 * _tmp83 - _tmp86 * _tmp87 + _tmp93; - _p_new(1, 4) = _tmp37 * _tmp75 + _tmp38 * _tmp91 + _tmp39 * _tmp68 + _tmp40 * _tmp65 - - _tmp78 * _tmp95 - _tmp82 * _tmp96 - _tmp86 * _tmp94 + _tmp98; - _p_new(2, 4) = -_tmp100 * _tmp82 - _tmp101 * _tmp86 + _tmp102 + _tmp47 * _tmp68 + - _tmp48 * _tmp65 + _tmp49 * _tmp75 + _tmp50 * _tmp91 - _tmp78 * _tmp99; - _p_new(3, 4) = -_tmp103 * _tmp86 - _tmp104 * _tmp82 - _tmp105 * _tmp78 + _tmp106 + - _tmp55 * _tmp91 + _tmp56 * _tmp68 + _tmp57 * _tmp65 + _tmp58 * _tmp75; - _p_new(4, 4) = -_tmp107 * _tmp86 - _tmp108 * _tmp82 - _tmp109 * _tmp78 + _tmp110 * _tmp68 + - _tmp111 * _tmp65 + _tmp112 * _tmp91 + _tmp113 * _tmp75 + _tmp114 + - std::pow(_tmp78, Scalar(2)) * d_vel_var(2, 0) + - std::pow(_tmp82, Scalar(2)) * d_vel_var(1, 0) + - std::pow(_tmp86, Scalar(2)) * d_vel_var(0, 0); + _p_new(0, 4) = _tmp16 * _tmp91 + _tmp17 * _tmp83 + _tmp18 * _tmp88 + _tmp22 * _tmp80 - + _tmp57 * _tmp61 - _tmp62 * _tmp68 - _tmp69 * _tmp73 + _tmp92; + _p_new(1, 4) = _tmp35 * _tmp80 + _tmp36 * _tmp88 + _tmp37 * _tmp91 + _tmp39 * _tmp83 - + _tmp61 * _tmp93 - _tmp68 * _tmp94 - _tmp73 * _tmp95 + _tmp96; + _p_new(2, 4) = -_tmp101 * _tmp60 + _tmp102 + _tmp45 * _tmp88 + _tmp46 * _tmp83 + + _tmp47 * _tmp80 + _tmp48 * _tmp91 - _tmp68 * _tmp97 - _tmp72 * _tmp99; + _p_new(3, 4) = -_tmp103 * _tmp68 - _tmp104 * _tmp73 - _tmp105 * _tmp61 + _tmp106 + + _tmp53 * _tmp91 + _tmp54 * _tmp83 + _tmp55 * _tmp80 + _tmp56 * _tmp88; + _p_new(4, 4) = _tmp107 * _tmp83 + _tmp108 * _tmp80 - _tmp109 * _tmp61 - _tmp110 * _tmp68 - + _tmp111 * _tmp73 + _tmp112 * _tmp88 + _tmp113 * _tmp91 + _tmp114 + + std::pow(_tmp60, Scalar(2)) * d_vel_var(0, 0) + + std::pow(_tmp67, Scalar(2)) * d_vel_var(2, 0) + + std::pow(_tmp72, Scalar(2)) * d_vel_var(1, 0); _p_new(5, 4) = 0; _p_new(6, 4) = 0; _p_new(7, 4) = 0; @@ -451,22 +454,21 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 4) = 0; _p_new(22, 4) = 0; _p_new(23, 4) = 0; - _p_new(0, 5) = _tmp116 * _tmp15 + _tmp118 * _tmp24 + _tmp120 * _tmp17 - _tmp121 * _tmp87 - - _tmp124 * _tmp79 - _tmp126 * _tmp83 + _tmp129 * _tmp19 + _tmp131; - _p_new(1, 5) = _tmp116 * _tmp38 + _tmp118 * _tmp39 + _tmp120 * _tmp37 - _tmp121 * _tmp94 - - _tmp124 * _tmp95 - _tmp126 * _tmp96 + _tmp129 * _tmp40 + _tmp132; - _p_new(2, 5) = -_tmp100 * _tmp126 - _tmp101 * _tmp121 + _tmp116 * _tmp50 + _tmp118 * _tmp47 + - _tmp120 * _tmp49 - _tmp124 * _tmp99 + _tmp129 * _tmp48 + _tmp133; - _p_new(3, 5) = -_tmp103 * _tmp121 - _tmp104 * _tmp126 - _tmp105 * _tmp124 + _tmp116 * _tmp55 + - _tmp118 * _tmp56 + _tmp120 * _tmp58 + _tmp129 * _tmp57 + _tmp134; - _p_new(4, 5) = -_tmp107 * _tmp121 - _tmp108 * _tmp126 - _tmp109 * _tmp124 + _tmp110 * _tmp118 + - _tmp111 * _tmp129 + _tmp112 * _tmp116 + _tmp113 * _tmp120 + _tmp121 * _tmp135 + - _tmp124 * _tmp137 + _tmp126 * _tmp136 + _tmp138; - _p_new(5, 5) = _tmp116 * _tmp145 + _tmp118 * _tmp144 + _tmp120 * _tmp140 + - std::pow(_tmp121, Scalar(2)) * d_vel_var(0, 0) - _tmp121 * _tmp141 + - std::pow(_tmp124, Scalar(2)) * d_vel_var(2, 0) - _tmp124 * _tmp142 + - std::pow(_tmp126, Scalar(2)) * d_vel_var(1, 0) - _tmp126 * _tmp143 + - _tmp129 * _tmp139 + _tmp146; + _p_new(0, 5) = -_tmp117 * _tmp69 - _tmp119 * _tmp57 + _tmp121 * _tmp16 + _tmp123 * _tmp22 + + _tmp126 * _tmp17 + _tmp128 * _tmp18 - _tmp132 * _tmp62 + _tmp133; + _p_new(1, 5) = -_tmp117 * _tmp95 - _tmp119 * _tmp93 + _tmp121 * _tmp37 + _tmp123 * _tmp35 + + _tmp126 * _tmp39 + _tmp128 * _tmp36 - _tmp132 * _tmp94 + _tmp134; + _p_new(2, 5) = -_tmp101 * _tmp118 - _tmp116 * _tmp99 + _tmp121 * _tmp48 + _tmp123 * _tmp47 + + _tmp126 * _tmp46 + _tmp128 * _tmp45 - _tmp132 * _tmp97 + _tmp135; + _p_new(3, 5) = -_tmp103 * _tmp132 - _tmp104 * _tmp117 - _tmp105 * _tmp119 + _tmp121 * _tmp53 + + _tmp123 * _tmp55 + _tmp126 * _tmp54 + _tmp128 * _tmp56 + _tmp136; + _p_new(4, 5) = _tmp107 * _tmp126 + _tmp108 * _tmp123 - _tmp109 * _tmp119 - _tmp110 * _tmp132 - + _tmp111 * _tmp117 + _tmp112 * _tmp128 + _tmp113 * _tmp121 + _tmp116 * _tmp138 + + _tmp131 * _tmp139 + _tmp137 * _tmp60 + _tmp140; + _p_new(5, 5) = std::pow(_tmp116, Scalar(2)) * d_vel_var(1, 0) - _tmp117 * _tmp143 + + std::pow(_tmp118, Scalar(2)) * d_vel_var(0, 0) - _tmp118 * _tmp148 + + _tmp121 * _tmp142 + _tmp123 * _tmp141 + _tmp126 * _tmp146 + _tmp128 * _tmp145 + + std::pow(_tmp131, Scalar(2)) * d_vel_var(2, 0) - _tmp132 * _tmp144 + _tmp149; _p_new(6, 5) = 0; _p_new(7, 5) = 0; _p_new(8, 5) = 0; @@ -485,33 +487,33 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 5) = 0; _p_new(22, 5) = 0; _p_new(23, 5) = 0; - _p_new(0, 6) = _tmp147 * _tmp17 + _tmp148 * _tmp24 + _tmp149 * _tmp15 + _tmp150 * _tmp19 - - _tmp151 * _tmp87 - _tmp152 * _tmp83 - _tmp153 * _tmp79 + _tmp155; - _p_new(1, 6) = _tmp147 * _tmp37 + _tmp148 * _tmp39 + _tmp149 * _tmp38 + _tmp150 * _tmp40 - - _tmp151 * _tmp94 - _tmp152 * _tmp96 - _tmp153 * _tmp95 + _tmp156; - _p_new(2, 6) = -_tmp100 * _tmp152 - _tmp101 * _tmp151 + _tmp147 * _tmp49 + _tmp148 * _tmp47 + - _tmp149 * _tmp50 + _tmp150 * _tmp48 - _tmp153 * _tmp99 + _tmp157; - _p_new(3, 6) = -_tmp103 * _tmp151 - _tmp104 * _tmp152 - _tmp105 * _tmp153 + _tmp147 * _tmp58 + - _tmp148 * _tmp56 + _tmp149 * _tmp55 + _tmp150 * _tmp57 + _tmp158; - _p_new(4, 6) = -_tmp107 * _tmp151 - _tmp108 * _tmp152 - _tmp109 * _tmp153 + _tmp110 * _tmp148 + - _tmp111 * _tmp150 + _tmp112 * _tmp149 + _tmp113 * _tmp147 + _tmp135 * _tmp151 + - _tmp136 * _tmp152 + _tmp137 * _tmp153 + _tmp159; - _p_new(5, 6) = _tmp121 * _tmp151 * d_vel_var(0, 0) + _tmp124 * _tmp153 * d_vel_var(2, 0) + - _tmp126 * _tmp152 * d_vel_var(1, 0) + _tmp139 * _tmp150 + _tmp140 * _tmp147 - - _tmp141 * _tmp151 - _tmp142 * _tmp153 - _tmp143 * _tmp152 + _tmp144 * _tmp148 + - _tmp145 * _tmp149 + _tmp160; + _p_new(0, 6) = -_tmp151 * _tmp62 - _tmp153 * _tmp57 + _tmp154 * _tmp22 + _tmp155 * _tmp18 + + _tmp157 * _tmp17 + _tmp158 * _tmp16 - _tmp160 * _tmp69 + _tmp162; + _p_new(1, 6) = -_tmp151 * _tmp94 - _tmp153 * _tmp93 + _tmp154 * _tmp35 + _tmp155 * _tmp36 + + _tmp157 * _tmp39 + _tmp158 * _tmp37 - _tmp160 * _tmp95 + _tmp163; + _p_new(2, 6) = -_tmp101 * _tmp152 - _tmp151 * _tmp97 + _tmp154 * _tmp47 + _tmp155 * _tmp45 + + _tmp157 * _tmp46 + _tmp158 * _tmp48 - _tmp159 * _tmp99 + _tmp164; + _p_new(3, 6) = -_tmp103 * _tmp151 - _tmp104 * _tmp160 - _tmp105 * _tmp153 + _tmp154 * _tmp55 + + _tmp155 * _tmp56 + _tmp157 * _tmp54 + _tmp158 * _tmp53 + _tmp165; + _p_new(4, 6) = _tmp107 * _tmp157 + _tmp108 * _tmp154 - _tmp109 * _tmp153 - _tmp110 * _tmp151 - + _tmp111 * _tmp160 + _tmp112 * _tmp155 + _tmp113 * _tmp158 + _tmp138 * _tmp159 + + _tmp139 * _tmp150 + _tmp152 * _tmp60 * d_vel_var(0, 0) + _tmp166; + _p_new(5, 6) = _tmp116 * _tmp159 * d_vel_var(1, 0) + _tmp131 * _tmp150 * d_vel_var(2, 0) + + _tmp137 * _tmp152 + _tmp141 * _tmp154 + _tmp142 * _tmp158 - _tmp143 * _tmp160 - + _tmp144 * _tmp151 + _tmp145 * _tmp155 + _tmp146 * _tmp157 - _tmp148 * _tmp152 + + _tmp167; _p_new(6, 6) = - _tmp147 * (P(0, 3) * _tmp148 + P(1, 3) * _tmp150 - P(13, 3) * _tmp151 - P(14, 3) * _tmp152 - - P(15, 3) * _tmp153 + P(2, 3) * _tmp149 + P(3, 3) * _tmp147 + P(6, 3)) + - _tmp148 * (P(0, 0) * _tmp148 + P(1, 0) * _tmp150 - P(13, 0) * _tmp151 - P(14, 0) * _tmp152 - - P(15, 0) * _tmp153 + P(2, 0) * _tmp149 + P(3, 0) * _tmp147 + P(6, 0)) + - _tmp149 * (P(0, 2) * _tmp148 + P(1, 2) * _tmp150 - P(13, 2) * _tmp151 - P(14, 2) * _tmp152 - - P(15, 2) * _tmp153 + P(2, 2) * _tmp149 + P(3, 2) * _tmp147 + P(6, 2)) + - _tmp150 * (P(0, 1) * _tmp148 + P(1, 1) * _tmp150 - P(13, 1) * _tmp151 - P(14, 1) * _tmp152 - - P(15, 1) * _tmp153 + P(2, 1) * _tmp149 + P(3, 1) * _tmp147 + P(6, 1)) + - std::pow(_tmp151, Scalar(2)) * d_vel_var(0, 0) - _tmp151 * _tmp161 + - std::pow(_tmp152, Scalar(2)) * d_vel_var(1, 0) - _tmp152 * _tmp162 + - std::pow(_tmp153, Scalar(2)) * d_vel_var(2, 0) - _tmp153 * _tmp163 + _tmp164; + std::pow(_tmp150, Scalar(2)) * d_vel_var(2, 0) - _tmp151 * _tmp169 + + std::pow(_tmp152, Scalar(2)) * d_vel_var(0, 0) - _tmp153 * _tmp168 + + _tmp154 * (P(0, 0) * _tmp154 + P(1, 0) * _tmp157 - P(13, 0) * _tmp153 - P(14, 0) * _tmp160 - + P(15, 0) * _tmp151 + P(2, 0) * _tmp158 + P(3, 0) * _tmp155 + P(6, 0)) + + _tmp155 * (P(0, 3) * _tmp154 + P(1, 3) * _tmp157 - P(13, 3) * _tmp153 - P(14, 3) * _tmp160 - + P(15, 3) * _tmp151 + P(2, 3) * _tmp158 + P(3, 3) * _tmp155 + P(6, 3)) + + _tmp157 * (P(0, 1) * _tmp154 + P(1, 1) * _tmp157 - P(13, 1) * _tmp153 - P(14, 1) * _tmp160 - + P(15, 1) * _tmp151 + P(2, 1) * _tmp158 + P(3, 1) * _tmp155 + P(6, 1)) + + _tmp158 * (P(0, 2) * _tmp154 + P(1, 2) * _tmp157 - P(13, 2) * _tmp153 - P(14, 2) * _tmp160 - + P(15, 2) * _tmp151 + P(2, 2) * _tmp158 + P(3, 2) * _tmp155 + P(6, 2)) + + std::pow(_tmp159, Scalar(2)) * d_vel_var(1, 0) - _tmp160 * _tmp170 + _tmp171; _p_new(7, 6) = 0; _p_new(8, 6) = 0; _p_new(9, 6) = 0; @@ -529,26 +531,26 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 6) = 0; _p_new(22, 6) = 0; _p_new(23, 6) = 0; - _p_new(0, 7) = P(0, 7) + P(1, 7) * _tmp8 + P(10, 7) * _tmp11 + P(11, 7) * _tmp10 + - P(2, 7) * _tmp5 + P(3, 7) * _tmp2 + _tmp165 * state(3, 0) + _tmp93 * dt; - _p_new(1, 7) = P(0, 7) * _tmp33 + P(1, 7) - P(10, 7) * _tmp30 + P(11, 7) * _tmp9 + - P(2, 7) * _tmp32 + P(3, 7) * _tmp5 - _tmp165 * state(2, 0) + _tmp98 * dt; - _p_new(2, 7) = P(0, 7) * _tmp43 + P(1, 7) * _tmp2 - P(10, 7) * _tmp9 - P(11, 7) * _tmp30 + - P(2, 7) + P(3, 7) * _tmp33 + _tmp102 * dt + _tmp165 * state(1, 0); - _p_new(3, 7) = P(0, 7) * _tmp32 + P(1, 7) * _tmp43 + P(10, 7) * _tmp10 - P(11, 7) * _tmp11 + - P(2, 7) * _tmp8 + P(3, 7) + _tmp106 * dt - _tmp165 * state(0, 0); - _p_new(4, 7) = P(0, 7) * _tmp68 + P(1, 7) * _tmp65 - P(13, 7) * _tmp86 - P(14, 7) * _tmp82 - - P(15, 7) * _tmp78 + P(2, 7) * _tmp91 + P(3, 7) * _tmp75 + P(4, 7) + _tmp114 * dt; + _p_new(0, 7) = P(0, 7) + P(1, 7) * _tmp3 + P(10, 7) * _tmp12 + P(11, 7) * _tmp10 + + P(12, 7) * _tmp11 + P(2, 7) * _tmp9 + P(3, 7) * _tmp6 + _tmp92 * dt; + _p_new(1, 7) = P(0, 7) * _tmp30 + P(1, 7) - P(10, 7) * _tmp29 + P(11, 7) * _tmp11 - + P(12, 7) * _tmp10 + P(2, 7) * _tmp31 + P(3, 7) * _tmp9 + _tmp96 * dt; + _p_new(2, 7) = P(0, 7) * _tmp41 + P(1, 7) * _tmp6 - P(10, 7) * _tmp11 - P(11, 7) * _tmp29 + + P(12, 7) * _tmp12 + P(2, 7) + P(3, 7) * _tmp30 + _tmp102 * dt; + _p_new(3, 7) = P(0, 7) * _tmp31 + P(1, 7) * _tmp41 + P(10, 7) * _tmp10 - P(11, 7) * _tmp12 - + P(12, 7) * _tmp29 + P(2, 7) * _tmp3 + P(3, 7) + _tmp106 * dt; + _p_new(4, 7) = P(0, 7) * _tmp80 + P(1, 7) * _tmp83 - P(13, 7) * _tmp61 - P(14, 7) * _tmp73 - + P(15, 7) * _tmp68 + P(2, 7) * _tmp91 + P(3, 7) * _tmp88 + P(4, 7) + _tmp114 * dt; _p_new(5, 7) = - P(0, 7) * _tmp118 + P(1, 7) * _tmp129 - P(13, 7) * _tmp121 - P(14, 7) * _tmp126 - - P(15, 7) * _tmp124 + P(2, 7) * _tmp116 + P(3, 7) * _tmp120 + P(5, 7) + - dt * (P(0, 4) * _tmp118 + P(1, 4) * _tmp129 - P(13, 4) * _tmp121 - P(14, 4) * _tmp126 - - P(15, 4) * _tmp124 + P(2, 4) * _tmp116 + P(3, 4) * _tmp120 + P(5, 4)); + P(0, 7) * _tmp123 + P(1, 7) * _tmp126 - P(13, 7) * _tmp119 - P(14, 7) * _tmp117 - + P(15, 7) * _tmp132 + P(2, 7) * _tmp121 + P(3, 7) * _tmp128 + P(5, 7) + + dt * (P(0, 4) * _tmp123 + P(1, 4) * _tmp126 - P(13, 4) * _tmp119 - P(14, 4) * _tmp117 - + P(15, 4) * _tmp132 + P(2, 4) * _tmp121 + P(3, 4) * _tmp128 + P(5, 4)); _p_new(6, 7) = - P(0, 7) * _tmp148 + P(1, 7) * _tmp150 - P(13, 7) * _tmp151 - P(14, 7) * _tmp152 - - P(15, 7) * _tmp153 + P(2, 7) * _tmp149 + P(3, 7) * _tmp147 + P(6, 7) + - dt * (P(0, 4) * _tmp148 + P(1, 4) * _tmp150 - P(13, 4) * _tmp151 - P(14, 4) * _tmp152 - - P(15, 4) * _tmp153 + P(2, 4) * _tmp149 + P(3, 4) * _tmp147 + P(6, 4)); + P(0, 7) * _tmp154 + P(1, 7) * _tmp157 - P(13, 7) * _tmp153 - P(14, 7) * _tmp160 - + P(15, 7) * _tmp151 + P(2, 7) * _tmp158 + P(3, 7) * _tmp155 + P(6, 7) + + dt * (P(0, 4) * _tmp154 + P(1, 4) * _tmp157 - P(13, 4) * _tmp153 - P(14, 4) * _tmp160 - + P(15, 4) * _tmp151 + P(2, 4) * _tmp158 + P(3, 4) * _tmp155 + P(6, 4)); _p_new(7, 7) = P(4, 7) * dt + P(7, 7) + dt * (P(4, 4) * dt + P(7, 4)); _p_new(8, 7) = 0; _p_new(9, 7) = 0; @@ -566,24 +568,24 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 7) = 0; _p_new(22, 7) = 0; _p_new(23, 7) = 0; - _p_new(0, 8) = P(0, 8) + P(1, 8) * _tmp8 + P(10, 8) * _tmp11 + P(12, 8) * _tmp9 + - P(2, 8) * _tmp5 + P(3, 8) * _tmp2 + _tmp131 * dt + _tmp166 * state(2, 0); - _p_new(1, 8) = P(0, 8) * _tmp33 + P(1, 8) - P(10, 8) * _tmp30 + P(2, 8) * _tmp32 + - P(3, 8) * _tmp5 + _tmp132 * dt + _tmp166 * state(3, 0) - _tmp167 * state(2, 0); - _p_new(2, 8) = P(0, 8) * _tmp43 + P(1, 8) * _tmp2 - P(10, 8) * _tmp9 + P(12, 8) * _tmp11 + - P(2, 8) + P(3, 8) * _tmp33 + _tmp133 * dt - _tmp166 * state(0, 0); - _p_new(3, 8) = P(0, 8) * _tmp32 + P(1, 8) * _tmp43 + P(10, 8) * _tmp10 + P(2, 8) * _tmp8 + - P(3, 8) + _tmp134 * dt - _tmp166 * state(1, 0) - _tmp167 * state(0, 0); - _p_new(4, 8) = P(0, 8) * _tmp68 + P(1, 8) * _tmp65 - P(13, 8) * _tmp86 - P(14, 8) * _tmp82 - - P(15, 8) * _tmp78 + P(2, 8) * _tmp91 + P(3, 8) * _tmp75 + P(4, 8) + _tmp138 * dt; - _p_new(5, 8) = P(0, 8) * _tmp118 + P(1, 8) * _tmp129 - P(13, 8) * _tmp121 - P(14, 8) * _tmp126 - - P(15, 8) * _tmp124 + P(2, 8) * _tmp116 + P(3, 8) * _tmp120 + P(5, 8) + - _tmp146 * dt; + _p_new(0, 8) = P(0, 8) + P(1, 8) * _tmp3 + P(10, 8) * _tmp12 + P(12, 8) * _tmp11 + + P(2, 8) * _tmp9 + P(3, 8) * _tmp6 + _tmp133 * dt + _tmp172 * state(2, 0); + _p_new(1, 8) = P(0, 8) * _tmp30 + P(1, 8) - P(10, 8) * _tmp29 - P(12, 8) * _tmp10 + + P(2, 8) * _tmp31 + P(3, 8) * _tmp9 + _tmp134 * dt + _tmp172 * state(3, 0); + _p_new(2, 8) = P(0, 8) * _tmp41 + P(1, 8) * _tmp6 - P(10, 8) * _tmp11 + P(12, 8) * _tmp12 + + P(2, 8) + P(3, 8) * _tmp30 + _tmp135 * dt - _tmp172 * state(0, 0); + _p_new(3, 8) = P(0, 8) * _tmp31 + P(1, 8) * _tmp41 + P(10, 8) * _tmp10 - P(11, 8) * _tmp12 - + P(12, 8) * _tmp29 + P(2, 8) * _tmp3 + P(3, 8) + _tmp136 * dt; + _p_new(4, 8) = P(0, 8) * _tmp80 + P(1, 8) * _tmp83 - P(13, 8) * _tmp61 - P(14, 8) * _tmp73 - + P(15, 8) * _tmp68 + P(2, 8) * _tmp91 + P(3, 8) * _tmp88 + P(4, 8) + _tmp140 * dt; + _p_new(5, 8) = P(0, 8) * _tmp123 + P(1, 8) * _tmp126 - P(13, 8) * _tmp119 - P(14, 8) * _tmp117 - + P(15, 8) * _tmp132 + P(2, 8) * _tmp121 + P(3, 8) * _tmp128 + P(5, 8) + + _tmp149 * dt; _p_new(6, 8) = - P(0, 8) * _tmp148 + P(1, 8) * _tmp150 - P(13, 8) * _tmp151 - P(14, 8) * _tmp152 - - P(15, 8) * _tmp153 + P(2, 8) * _tmp149 + P(3, 8) * _tmp147 + P(6, 8) + - dt * (P(0, 5) * _tmp148 + P(1, 5) * _tmp150 - P(13, 5) * _tmp151 - P(14, 5) * _tmp152 - - P(15, 5) * _tmp153 + P(2, 5) * _tmp149 + P(3, 5) * _tmp147 + P(6, 5)); + P(0, 8) * _tmp154 + P(1, 8) * _tmp157 - P(13, 8) * _tmp153 - P(14, 8) * _tmp160 - + P(15, 8) * _tmp151 + P(2, 8) * _tmp158 + P(3, 8) * _tmp155 + P(6, 8) + + dt * (P(0, 5) * _tmp154 + P(1, 5) * _tmp157 - P(13, 5) * _tmp153 - P(14, 5) * _tmp160 - + P(15, 5) * _tmp151 + P(2, 5) * _tmp158 + P(3, 5) * _tmp155 + P(6, 5)); _p_new(7, 8) = P(4, 8) * dt + P(7, 8) + dt * (P(4, 5) * dt + P(7, 5)); _p_new(8, 8) = P(5, 8) * dt + P(8, 8) + dt * (P(5, 5) * dt + P(8, 5)); _p_new(9, 8) = 0; @@ -601,22 +603,22 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 8) = 0; _p_new(22, 8) = 0; _p_new(23, 8) = 0; - _p_new(0, 9) = P(0, 9) + P(1, 9) * _tmp8 + P(10, 9) * _tmp11 + P(12, 9) * _tmp9 + - P(2, 9) * _tmp5 + P(3, 9) * _tmp2 + _tmp155 * dt + _tmp168 * state(2, 0); - _p_new(1, 9) = P(0, 9) * _tmp33 + P(1, 9) + P(11, 9) * _tmp9 + P(2, 9) * _tmp32 + - P(3, 9) * _tmp5 + _tmp156 * dt - _tmp169 * state(0, 0) - _tmp170 * state(2, 0); - _p_new(2, 9) = P(0, 9) * _tmp43 + P(1, 9) * _tmp2 - P(10, 9) * _tmp9 + P(12, 9) * _tmp11 + - P(2, 9) + P(3, 9) * _tmp33 + _tmp157 * dt - _tmp168 * state(0, 0); - _p_new(3, 9) = P(0, 9) * _tmp32 + P(1, 9) * _tmp43 - P(11, 9) * _tmp11 + P(2, 9) * _tmp8 + - P(3, 9) + _tmp158 * dt + _tmp169 * state(2, 0) - _tmp170 * state(0, 0); - _p_new(4, 9) = P(0, 9) * _tmp68 + P(1, 9) * _tmp65 - P(13, 9) * _tmp86 - P(14, 9) * _tmp82 - - P(15, 9) * _tmp78 + P(2, 9) * _tmp91 + P(3, 9) * _tmp75 + P(4, 9) + _tmp159 * dt; - _p_new(5, 9) = P(0, 9) * _tmp118 + P(1, 9) * _tmp129 - P(13, 9) * _tmp121 - P(14, 9) * _tmp126 - - P(15, 9) * _tmp124 + P(2, 9) * _tmp116 + P(3, 9) * _tmp120 + P(5, 9) + - _tmp160 * dt; - _p_new(6, 9) = P(0, 9) * _tmp148 + P(1, 9) * _tmp150 - P(13, 9) * _tmp151 - P(14, 9) * _tmp152 - - P(15, 9) * _tmp153 + P(2, 9) * _tmp149 + P(3, 9) * _tmp147 + P(6, 9) + - _tmp164 * dt; + _p_new(0, 9) = P(0, 9) + P(1, 9) * _tmp3 + P(10, 9) * _tmp12 + P(12, 9) * _tmp11 + + P(2, 9) * _tmp9 + P(3, 9) * _tmp6 + _tmp162 * dt + _tmp173 * state(2, 0); + _p_new(1, 9) = P(0, 9) * _tmp30 + P(1, 9) - P(10, 9) * _tmp29 - P(12, 9) * _tmp10 + + P(2, 9) * _tmp31 + P(3, 9) * _tmp9 + _tmp163 * dt + _tmp173 * state(3, 0); + _p_new(2, 9) = P(0, 9) * _tmp41 + P(1, 9) * _tmp6 - P(10, 9) * _tmp11 + P(12, 9) * _tmp12 + + P(2, 9) + P(3, 9) * _tmp30 + _tmp164 * dt - _tmp173 * state(0, 0); + _p_new(3, 9) = P(0, 9) * _tmp31 + P(1, 9) * _tmp41 + P(10, 9) * _tmp10 - P(11, 9) * _tmp12 - + P(12, 9) * _tmp29 + P(2, 9) * _tmp3 + P(3, 9) + _tmp165 * dt; + _p_new(4, 9) = P(0, 9) * _tmp80 + P(1, 9) * _tmp83 - P(13, 9) * _tmp61 - P(14, 9) * _tmp73 - + P(15, 9) * _tmp68 + P(2, 9) * _tmp91 + P(3, 9) * _tmp88 + P(4, 9) + _tmp166 * dt; + _p_new(5, 9) = P(0, 9) * _tmp123 + P(1, 9) * _tmp126 - P(13, 9) * _tmp119 - P(14, 9) * _tmp117 - + P(15, 9) * _tmp132 + P(2, 9) * _tmp121 + P(3, 9) * _tmp128 + P(5, 9) + + _tmp167 * dt; + _p_new(6, 9) = P(0, 9) * _tmp154 + P(1, 9) * _tmp157 - P(13, 9) * _tmp153 - P(14, 9) * _tmp160 - + P(15, 9) * _tmp151 + P(2, 9) * _tmp158 + P(3, 9) * _tmp155 + P(6, 9) + + _tmp171 * dt; _p_new(7, 9) = P(4, 9) * dt + P(7, 9) + dt * (P(4, 6) * dt + P(7, 6)); _p_new(8, 9) = P(5, 9) * dt + P(8, 9) + dt * (P(5, 6) * dt + P(8, 6)); _p_new(9, 9) = P(6, 9) * dt + P(9, 9) + dt * (P(6, 6) * dt + P(9, 6)); @@ -634,19 +636,19 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 9) = 0; _p_new(22, 9) = 0; _p_new(23, 9) = 0; - _p_new(0, 10) = _tmp13; - _p_new(1, 10) = _tmp36; - _p_new(2, 10) = _tmp46; - _p_new(3, 10) = _tmp54; - _p_new(4, 10) = P(0, 10) * _tmp68 + P(1, 10) * _tmp65 - P(13, 10) * _tmp86 - - P(14, 10) * _tmp82 - P(15, 10) * _tmp78 + P(2, 10) * _tmp91 + - P(3, 10) * _tmp75 + P(4, 10); - _p_new(5, 10) = P(0, 10) * _tmp118 + P(1, 10) * _tmp129 - P(13, 10) * _tmp121 - - P(14, 10) * _tmp126 - P(15, 10) * _tmp124 + P(2, 10) * _tmp116 + - P(3, 10) * _tmp120 + P(5, 10); - _p_new(6, 10) = P(0, 10) * _tmp148 + P(1, 10) * _tmp150 - P(13, 10) * _tmp151 - - P(14, 10) * _tmp152 - P(15, 10) * _tmp153 + P(2, 10) * _tmp149 + - P(3, 10) * _tmp147 + P(6, 10); + _p_new(0, 10) = _tmp15; + _p_new(1, 10) = _tmp32; + _p_new(2, 10) = _tmp43; + _p_new(3, 10) = _tmp50; + _p_new(4, 10) = P(0, 10) * _tmp80 + P(1, 10) * _tmp83 - P(13, 10) * _tmp61 - + P(14, 10) * _tmp73 - P(15, 10) * _tmp68 + P(2, 10) * _tmp91 + + P(3, 10) * _tmp88 + P(4, 10); + _p_new(5, 10) = P(0, 10) * _tmp123 + P(1, 10) * _tmp126 - P(13, 10) * _tmp119 - + P(14, 10) * _tmp117 - P(15, 10) * _tmp132 + P(2, 10) * _tmp121 + + P(3, 10) * _tmp128 + P(5, 10); + _p_new(6, 10) = P(0, 10) * _tmp154 + P(1, 10) * _tmp157 - P(13, 10) * _tmp153 - + P(14, 10) * _tmp160 - P(15, 10) * _tmp151 + P(2, 10) * _tmp158 + + P(3, 10) * _tmp155 + P(6, 10); _p_new(7, 10) = P(4, 10) * dt + P(7, 10); _p_new(8, 10) = P(5, 10) * dt + P(8, 10); _p_new(9, 10) = P(6, 10) * dt + P(9, 10); @@ -664,19 +666,19 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 10) = 0; _p_new(22, 10) = 0; _p_new(23, 10) = 0; - _p_new(0, 11) = _tmp12; - _p_new(1, 11) = _tmp35; - _p_new(2, 11) = _tmp45; - _p_new(3, 11) = _tmp53; - _p_new(4, 11) = P(0, 11) * _tmp68 + P(1, 11) * _tmp65 - P(13, 11) * _tmp86 - - P(14, 11) * _tmp82 - P(15, 11) * _tmp78 + P(2, 11) * _tmp91 + - P(3, 11) * _tmp75 + P(4, 11); - _p_new(5, 11) = P(0, 11) * _tmp118 + P(1, 11) * _tmp129 - P(13, 11) * _tmp121 - - P(14, 11) * _tmp126 - P(15, 11) * _tmp124 + P(2, 11) * _tmp116 + - P(3, 11) * _tmp120 + P(5, 11); - _p_new(6, 11) = P(0, 11) * _tmp148 + P(1, 11) * _tmp150 - P(13, 11) * _tmp151 - - P(14, 11) * _tmp152 - P(15, 11) * _tmp153 + P(2, 11) * _tmp149 + - P(3, 11) * _tmp147 + P(6, 11); + _p_new(0, 11) = _tmp14; + _p_new(1, 11) = _tmp33; + _p_new(2, 11) = _tmp42; + _p_new(3, 11) = _tmp51; + _p_new(4, 11) = P(0, 11) * _tmp80 + P(1, 11) * _tmp83 - P(13, 11) * _tmp61 - + P(14, 11) * _tmp73 - P(15, 11) * _tmp68 + P(2, 11) * _tmp91 + + P(3, 11) * _tmp88 + P(4, 11); + _p_new(5, 11) = P(0, 11) * _tmp123 + P(1, 11) * _tmp126 - P(13, 11) * _tmp119 - + P(14, 11) * _tmp117 - P(15, 11) * _tmp132 + P(2, 11) * _tmp121 + + P(3, 11) * _tmp128 + P(5, 11); + _p_new(6, 11) = P(0, 11) * _tmp154 + P(1, 11) * _tmp157 - P(13, 11) * _tmp153 - + P(14, 11) * _tmp160 - P(15, 11) * _tmp151 + P(2, 11) * _tmp158 + + P(3, 11) * _tmp155 + P(6, 11); _p_new(7, 11) = P(4, 11) * dt + P(7, 11); _p_new(8, 11) = P(5, 11) * dt + P(8, 11); _p_new(9, 11) = P(6, 11) * dt + P(9, 11); @@ -694,19 +696,19 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 11) = 0; _p_new(22, 11) = 0; _p_new(23, 11) = 0; - _p_new(0, 12) = _tmp14; + _p_new(0, 12) = _tmp13; _p_new(1, 12) = _tmp34; _p_new(2, 12) = _tmp44; _p_new(3, 12) = _tmp52; - _p_new(4, 12) = P(0, 12) * _tmp68 + P(1, 12) * _tmp65 - P(13, 12) * _tmp86 - - P(14, 12) * _tmp82 - P(15, 12) * _tmp78 + P(2, 12) * _tmp91 + - P(3, 12) * _tmp75 + P(4, 12); - _p_new(5, 12) = P(0, 12) * _tmp118 + P(1, 12) * _tmp129 - P(13, 12) * _tmp121 - - P(14, 12) * _tmp126 - P(15, 12) * _tmp124 + P(2, 12) * _tmp116 + - P(3, 12) * _tmp120 + P(5, 12); - _p_new(6, 12) = P(0, 12) * _tmp148 + P(1, 12) * _tmp150 - P(13, 12) * _tmp151 - - P(14, 12) * _tmp152 - P(15, 12) * _tmp153 + P(2, 12) * _tmp149 + - P(3, 12) * _tmp147 + P(6, 12); + _p_new(4, 12) = P(0, 12) * _tmp80 + P(1, 12) * _tmp83 - P(13, 12) * _tmp61 - + P(14, 12) * _tmp73 - P(15, 12) * _tmp68 + P(2, 12) * _tmp91 + + P(3, 12) * _tmp88 + P(4, 12); + _p_new(5, 12) = P(0, 12) * _tmp123 + P(1, 12) * _tmp126 - P(13, 12) * _tmp119 - + P(14, 12) * _tmp117 - P(15, 12) * _tmp132 + P(2, 12) * _tmp121 + + P(3, 12) * _tmp128 + P(5, 12); + _p_new(6, 12) = P(0, 12) * _tmp154 + P(1, 12) * _tmp157 - P(13, 12) * _tmp153 - + P(14, 12) * _tmp160 - P(15, 12) * _tmp151 + P(2, 12) * _tmp158 + + P(3, 12) * _tmp155 + P(6, 12); _p_new(7, 12) = P(4, 12) * dt + P(7, 12); _p_new(8, 12) = P(5, 12) * dt + P(8, 12); _p_new(9, 12) = P(6, 12) * dt + P(9, 12); @@ -724,13 +726,13 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 12) = 0; _p_new(22, 12) = 0; _p_new(23, 12) = 0; - _p_new(0, 13) = _tmp87; - _p_new(1, 13) = _tmp94; - _p_new(2, 13) = _tmp101; - _p_new(3, 13) = _tmp103; - _p_new(4, 13) = _tmp107; - _p_new(5, 13) = _tmp141; - _p_new(6, 13) = _tmp161; + _p_new(0, 13) = _tmp57; + _p_new(1, 13) = _tmp93; + _p_new(2, 13) = _tmp100; + _p_new(3, 13) = _tmp105; + _p_new(4, 13) = _tmp109; + _p_new(5, 13) = _tmp147; + _p_new(6, 13) = _tmp168; _p_new(7, 13) = P(4, 13) * dt + P(7, 13); _p_new(8, 13) = P(5, 13) * dt + P(8, 13); _p_new(9, 13) = P(6, 13) * dt + P(9, 13); @@ -748,13 +750,13 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 13) = 0; _p_new(22, 13) = 0; _p_new(23, 13) = 0; - _p_new(0, 14) = _tmp83; - _p_new(1, 14) = _tmp96; - _p_new(2, 14) = _tmp100; + _p_new(0, 14) = _tmp69; + _p_new(1, 14) = _tmp95; + _p_new(2, 14) = _tmp98; _p_new(3, 14) = _tmp104; - _p_new(4, 14) = _tmp108; + _p_new(4, 14) = _tmp111; _p_new(5, 14) = _tmp143; - _p_new(6, 14) = _tmp162; + _p_new(6, 14) = _tmp170; _p_new(7, 14) = P(4, 14) * dt + P(7, 14); _p_new(8, 14) = P(5, 14) * dt + P(8, 14); _p_new(9, 14) = P(6, 14) * dt + P(9, 14); @@ -772,13 +774,13 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 14) = 0; _p_new(22, 14) = 0; _p_new(23, 14) = 0; - _p_new(0, 15) = _tmp79; - _p_new(1, 15) = _tmp95; - _p_new(2, 15) = _tmp99; - _p_new(3, 15) = _tmp105; - _p_new(4, 15) = _tmp109; - _p_new(5, 15) = _tmp142; - _p_new(6, 15) = _tmp163; + _p_new(0, 15) = _tmp62; + _p_new(1, 15) = _tmp94; + _p_new(2, 15) = _tmp97; + _p_new(3, 15) = _tmp103; + _p_new(4, 15) = _tmp110; + _p_new(5, 15) = _tmp144; + _p_new(6, 15) = _tmp169; _p_new(7, 15) = P(4, 15) * dt + P(7, 15); _p_new(8, 15) = P(5, 15) * dt + P(8, 15); _p_new(9, 15) = P(6, 15) * dt + P(9, 15); @@ -796,23 +798,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 15) = 0; _p_new(22, 15) = 0; _p_new(23, 15) = 0; - _p_new(0, 16) = P(0, 16) + P(1, 16) * _tmp8 + P(10, 16) * _tmp11 + P(11, 16) * _tmp10 + - P(12, 16) * _tmp9 + P(2, 16) * _tmp5 + P(3, 16) * _tmp2; - _p_new(1, 16) = P(0, 16) * _tmp33 + P(1, 16) - P(10, 16) * _tmp30 + P(11, 16) * _tmp9 - - P(12, 16) * _tmp10 + P(2, 16) * _tmp32 + P(3, 16) * _tmp5; - _p_new(2, 16) = P(0, 16) * _tmp43 + P(1, 16) * _tmp2 - P(10, 16) * _tmp9 - P(11, 16) * _tmp30 + - P(12, 16) * _tmp11 + P(2, 16) + P(3, 16) * _tmp33; - _p_new(3, 16) = P(0, 16) * _tmp32 + P(1, 16) * _tmp43 + P(10, 16) * _tmp10 - - P(11, 16) * _tmp11 - P(12, 16) * _tmp30 + P(2, 16) * _tmp8 + P(3, 16); - _p_new(4, 16) = P(0, 16) * _tmp68 + P(1, 16) * _tmp65 - P(13, 16) * _tmp86 - - P(14, 16) * _tmp82 - P(15, 16) * _tmp78 + P(2, 16) * _tmp91 + - P(3, 16) * _tmp75 + P(4, 16); - _p_new(5, 16) = P(0, 16) * _tmp118 + P(1, 16) * _tmp129 - P(13, 16) * _tmp121 - - P(14, 16) * _tmp126 - P(15, 16) * _tmp124 + P(2, 16) * _tmp116 + - P(3, 16) * _tmp120 + P(5, 16); - _p_new(6, 16) = P(0, 16) * _tmp148 + P(1, 16) * _tmp150 - P(13, 16) * _tmp151 - - P(14, 16) * _tmp152 - P(15, 16) * _tmp153 + P(2, 16) * _tmp149 + - P(3, 16) * _tmp147 + P(6, 16); + _p_new(0, 16) = P(0, 16) + P(1, 16) * _tmp3 + P(10, 16) * _tmp12 + P(11, 16) * _tmp10 + + P(12, 16) * _tmp11 + P(2, 16) * _tmp9 + P(3, 16) * _tmp6; + _p_new(1, 16) = P(0, 16) * _tmp30 + P(1, 16) - P(10, 16) * _tmp29 + P(11, 16) * _tmp11 - + P(12, 16) * _tmp10 + P(2, 16) * _tmp31 + P(3, 16) * _tmp9; + _p_new(2, 16) = P(0, 16) * _tmp41 + P(1, 16) * _tmp6 - P(10, 16) * _tmp11 - P(11, 16) * _tmp29 + + P(12, 16) * _tmp12 + P(2, 16) + P(3, 16) * _tmp30; + _p_new(3, 16) = P(0, 16) * _tmp31 + P(1, 16) * _tmp41 + P(10, 16) * _tmp10 - + P(11, 16) * _tmp12 - P(12, 16) * _tmp29 + P(2, 16) * _tmp3 + P(3, 16); + _p_new(4, 16) = P(0, 16) * _tmp80 + P(1, 16) * _tmp83 - P(13, 16) * _tmp61 - + P(14, 16) * _tmp73 - P(15, 16) * _tmp68 + P(2, 16) * _tmp91 + + P(3, 16) * _tmp88 + P(4, 16); + _p_new(5, 16) = P(0, 16) * _tmp123 + P(1, 16) * _tmp126 - P(13, 16) * _tmp119 - + P(14, 16) * _tmp117 - P(15, 16) * _tmp132 + P(2, 16) * _tmp121 + + P(3, 16) * _tmp128 + P(5, 16); + _p_new(6, 16) = P(0, 16) * _tmp154 + P(1, 16) * _tmp157 - P(13, 16) * _tmp153 - + P(14, 16) * _tmp160 - P(15, 16) * _tmp151 + P(2, 16) * _tmp158 + + P(3, 16) * _tmp155 + P(6, 16); _p_new(7, 16) = P(4, 16) * dt + P(7, 16); _p_new(8, 16) = P(5, 16) * dt + P(8, 16); _p_new(9, 16) = P(6, 16) * dt + P(9, 16); @@ -830,23 +832,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 16) = 0; _p_new(22, 16) = 0; _p_new(23, 16) = 0; - _p_new(0, 17) = P(0, 17) + P(1, 17) * _tmp8 + P(10, 17) * _tmp11 + P(11, 17) * _tmp10 + - P(12, 17) * _tmp9 + P(2, 17) * _tmp5 + P(3, 17) * _tmp2; - _p_new(1, 17) = P(0, 17) * _tmp33 + P(1, 17) - P(10, 17) * _tmp30 + P(11, 17) * _tmp9 - - P(12, 17) * _tmp10 + P(2, 17) * _tmp32 + P(3, 17) * _tmp5; - _p_new(2, 17) = P(0, 17) * _tmp43 + P(1, 17) * _tmp2 - P(10, 17) * _tmp9 - P(11, 17) * _tmp30 + - P(12, 17) * _tmp11 + P(2, 17) + P(3, 17) * _tmp33; - _p_new(3, 17) = P(0, 17) * _tmp32 + P(1, 17) * _tmp43 + P(10, 17) * _tmp10 - - P(11, 17) * _tmp11 - P(12, 17) * _tmp30 + P(2, 17) * _tmp8 + P(3, 17); - _p_new(4, 17) = P(0, 17) * _tmp68 + P(1, 17) * _tmp65 - P(13, 17) * _tmp86 - - P(14, 17) * _tmp82 - P(15, 17) * _tmp78 + P(2, 17) * _tmp91 + - P(3, 17) * _tmp75 + P(4, 17); - _p_new(5, 17) = P(0, 17) * _tmp118 + P(1, 17) * _tmp129 - P(13, 17) * _tmp121 - - P(14, 17) * _tmp126 - P(15, 17) * _tmp124 + P(2, 17) * _tmp116 + - P(3, 17) * _tmp120 + P(5, 17); - _p_new(6, 17) = P(0, 17) * _tmp148 + P(1, 17) * _tmp150 - P(13, 17) * _tmp151 - - P(14, 17) * _tmp152 - P(15, 17) * _tmp153 + P(2, 17) * _tmp149 + - P(3, 17) * _tmp147 + P(6, 17); + _p_new(0, 17) = P(0, 17) + P(1, 17) * _tmp3 + P(10, 17) * _tmp12 + P(11, 17) * _tmp10 + + P(12, 17) * _tmp11 + P(2, 17) * _tmp9 + P(3, 17) * _tmp6; + _p_new(1, 17) = P(0, 17) * _tmp30 + P(1, 17) - P(10, 17) * _tmp29 + P(11, 17) * _tmp11 - + P(12, 17) * _tmp10 + P(2, 17) * _tmp31 + P(3, 17) * _tmp9; + _p_new(2, 17) = P(0, 17) * _tmp41 + P(1, 17) * _tmp6 - P(10, 17) * _tmp11 - P(11, 17) * _tmp29 + + P(12, 17) * _tmp12 + P(2, 17) + P(3, 17) * _tmp30; + _p_new(3, 17) = P(0, 17) * _tmp31 + P(1, 17) * _tmp41 + P(10, 17) * _tmp10 - + P(11, 17) * _tmp12 - P(12, 17) * _tmp29 + P(2, 17) * _tmp3 + P(3, 17); + _p_new(4, 17) = P(0, 17) * _tmp80 + P(1, 17) * _tmp83 - P(13, 17) * _tmp61 - + P(14, 17) * _tmp73 - P(15, 17) * _tmp68 + P(2, 17) * _tmp91 + + P(3, 17) * _tmp88 + P(4, 17); + _p_new(5, 17) = P(0, 17) * _tmp123 + P(1, 17) * _tmp126 - P(13, 17) * _tmp119 - + P(14, 17) * _tmp117 - P(15, 17) * _tmp132 + P(2, 17) * _tmp121 + + P(3, 17) * _tmp128 + P(5, 17); + _p_new(6, 17) = P(0, 17) * _tmp154 + P(1, 17) * _tmp157 - P(13, 17) * _tmp153 - + P(14, 17) * _tmp160 - P(15, 17) * _tmp151 + P(2, 17) * _tmp158 + + P(3, 17) * _tmp155 + P(6, 17); _p_new(7, 17) = P(4, 17) * dt + P(7, 17); _p_new(8, 17) = P(5, 17) * dt + P(8, 17); _p_new(9, 17) = P(6, 17) * dt + P(9, 17); @@ -864,23 +866,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 17) = 0; _p_new(22, 17) = 0; _p_new(23, 17) = 0; - _p_new(0, 18) = P(0, 18) + P(1, 18) * _tmp8 + P(10, 18) * _tmp11 + P(11, 18) * _tmp10 + - P(12, 18) * _tmp9 + P(2, 18) * _tmp5 + P(3, 18) * _tmp2; - _p_new(1, 18) = P(0, 18) * _tmp33 + P(1, 18) - P(10, 18) * _tmp30 + P(11, 18) * _tmp9 - - P(12, 18) * _tmp10 + P(2, 18) * _tmp32 + P(3, 18) * _tmp5; - _p_new(2, 18) = P(0, 18) * _tmp43 + P(1, 18) * _tmp2 - P(10, 18) * _tmp9 - P(11, 18) * _tmp30 + - P(12, 18) * _tmp11 + P(2, 18) + P(3, 18) * _tmp33; - _p_new(3, 18) = P(0, 18) * _tmp32 + P(1, 18) * _tmp43 + P(10, 18) * _tmp10 - - P(11, 18) * _tmp11 - P(12, 18) * _tmp30 + P(2, 18) * _tmp8 + P(3, 18); - _p_new(4, 18) = P(0, 18) * _tmp68 + P(1, 18) * _tmp65 - P(13, 18) * _tmp86 - - P(14, 18) * _tmp82 - P(15, 18) * _tmp78 + P(2, 18) * _tmp91 + - P(3, 18) * _tmp75 + P(4, 18); - _p_new(5, 18) = P(0, 18) * _tmp118 + P(1, 18) * _tmp129 - P(13, 18) * _tmp121 - - P(14, 18) * _tmp126 - P(15, 18) * _tmp124 + P(2, 18) * _tmp116 + - P(3, 18) * _tmp120 + P(5, 18); - _p_new(6, 18) = P(0, 18) * _tmp148 + P(1, 18) * _tmp150 - P(13, 18) * _tmp151 - - P(14, 18) * _tmp152 - P(15, 18) * _tmp153 + P(2, 18) * _tmp149 + - P(3, 18) * _tmp147 + P(6, 18); + _p_new(0, 18) = P(0, 18) + P(1, 18) * _tmp3 + P(10, 18) * _tmp12 + P(11, 18) * _tmp10 + + P(12, 18) * _tmp11 + P(2, 18) * _tmp9 + P(3, 18) * _tmp6; + _p_new(1, 18) = P(0, 18) * _tmp30 + P(1, 18) - P(10, 18) * _tmp29 + P(11, 18) * _tmp11 - + P(12, 18) * _tmp10 + P(2, 18) * _tmp31 + P(3, 18) * _tmp9; + _p_new(2, 18) = P(0, 18) * _tmp41 + P(1, 18) * _tmp6 - P(10, 18) * _tmp11 - P(11, 18) * _tmp29 + + P(12, 18) * _tmp12 + P(2, 18) + P(3, 18) * _tmp30; + _p_new(3, 18) = P(0, 18) * _tmp31 + P(1, 18) * _tmp41 + P(10, 18) * _tmp10 - + P(11, 18) * _tmp12 - P(12, 18) * _tmp29 + P(2, 18) * _tmp3 + P(3, 18); + _p_new(4, 18) = P(0, 18) * _tmp80 + P(1, 18) * _tmp83 - P(13, 18) * _tmp61 - + P(14, 18) * _tmp73 - P(15, 18) * _tmp68 + P(2, 18) * _tmp91 + + P(3, 18) * _tmp88 + P(4, 18); + _p_new(5, 18) = P(0, 18) * _tmp123 + P(1, 18) * _tmp126 - P(13, 18) * _tmp119 - + P(14, 18) * _tmp117 - P(15, 18) * _tmp132 + P(2, 18) * _tmp121 + + P(3, 18) * _tmp128 + P(5, 18); + _p_new(6, 18) = P(0, 18) * _tmp154 + P(1, 18) * _tmp157 - P(13, 18) * _tmp153 - + P(14, 18) * _tmp160 - P(15, 18) * _tmp151 + P(2, 18) * _tmp158 + + P(3, 18) * _tmp155 + P(6, 18); _p_new(7, 18) = P(4, 18) * dt + P(7, 18); _p_new(8, 18) = P(5, 18) * dt + P(8, 18); _p_new(9, 18) = P(6, 18) * dt + P(9, 18); @@ -898,23 +900,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 18) = 0; _p_new(22, 18) = 0; _p_new(23, 18) = 0; - _p_new(0, 19) = P(0, 19) + P(1, 19) * _tmp8 + P(10, 19) * _tmp11 + P(11, 19) * _tmp10 + - P(12, 19) * _tmp9 + P(2, 19) * _tmp5 + P(3, 19) * _tmp2; - _p_new(1, 19) = P(0, 19) * _tmp33 + P(1, 19) - P(10, 19) * _tmp30 + P(11, 19) * _tmp9 - - P(12, 19) * _tmp10 + P(2, 19) * _tmp32 + P(3, 19) * _tmp5; - _p_new(2, 19) = P(0, 19) * _tmp43 + P(1, 19) * _tmp2 - P(10, 19) * _tmp9 - P(11, 19) * _tmp30 + - P(12, 19) * _tmp11 + P(2, 19) + P(3, 19) * _tmp33; - _p_new(3, 19) = P(0, 19) * _tmp32 + P(1, 19) * _tmp43 + P(10, 19) * _tmp10 - - P(11, 19) * _tmp11 - P(12, 19) * _tmp30 + P(2, 19) * _tmp8 + P(3, 19); - _p_new(4, 19) = P(0, 19) * _tmp68 + P(1, 19) * _tmp65 - P(13, 19) * _tmp86 - - P(14, 19) * _tmp82 - P(15, 19) * _tmp78 + P(2, 19) * _tmp91 + - P(3, 19) * _tmp75 + P(4, 19); - _p_new(5, 19) = P(0, 19) * _tmp118 + P(1, 19) * _tmp129 - P(13, 19) * _tmp121 - - P(14, 19) * _tmp126 - P(15, 19) * _tmp124 + P(2, 19) * _tmp116 + - P(3, 19) * _tmp120 + P(5, 19); - _p_new(6, 19) = P(0, 19) * _tmp148 + P(1, 19) * _tmp150 - P(13, 19) * _tmp151 - - P(14, 19) * _tmp152 - P(15, 19) * _tmp153 + P(2, 19) * _tmp149 + - P(3, 19) * _tmp147 + P(6, 19); + _p_new(0, 19) = P(0, 19) + P(1, 19) * _tmp3 + P(10, 19) * _tmp12 + P(11, 19) * _tmp10 + + P(12, 19) * _tmp11 + P(2, 19) * _tmp9 + P(3, 19) * _tmp6; + _p_new(1, 19) = P(0, 19) * _tmp30 + P(1, 19) - P(10, 19) * _tmp29 + P(11, 19) * _tmp11 - + P(12, 19) * _tmp10 + P(2, 19) * _tmp31 + P(3, 19) * _tmp9; + _p_new(2, 19) = P(0, 19) * _tmp41 + P(1, 19) * _tmp6 - P(10, 19) * _tmp11 - P(11, 19) * _tmp29 + + P(12, 19) * _tmp12 + P(2, 19) + P(3, 19) * _tmp30; + _p_new(3, 19) = P(0, 19) * _tmp31 + P(1, 19) * _tmp41 + P(10, 19) * _tmp10 - + P(11, 19) * _tmp12 - P(12, 19) * _tmp29 + P(2, 19) * _tmp3 + P(3, 19); + _p_new(4, 19) = P(0, 19) * _tmp80 + P(1, 19) * _tmp83 - P(13, 19) * _tmp61 - + P(14, 19) * _tmp73 - P(15, 19) * _tmp68 + P(2, 19) * _tmp91 + + P(3, 19) * _tmp88 + P(4, 19); + _p_new(5, 19) = P(0, 19) * _tmp123 + P(1, 19) * _tmp126 - P(13, 19) * _tmp119 - + P(14, 19) * _tmp117 - P(15, 19) * _tmp132 + P(2, 19) * _tmp121 + + P(3, 19) * _tmp128 + P(5, 19); + _p_new(6, 19) = P(0, 19) * _tmp154 + P(1, 19) * _tmp157 - P(13, 19) * _tmp153 - + P(14, 19) * _tmp160 - P(15, 19) * _tmp151 + P(2, 19) * _tmp158 + + P(3, 19) * _tmp155 + P(6, 19); _p_new(7, 19) = P(4, 19) * dt + P(7, 19); _p_new(8, 19) = P(5, 19) * dt + P(8, 19); _p_new(9, 19) = P(6, 19) * dt + P(9, 19); @@ -932,23 +934,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 19) = 0; _p_new(22, 19) = 0; _p_new(23, 19) = 0; - _p_new(0, 20) = P(0, 20) + P(1, 20) * _tmp8 + P(10, 20) * _tmp11 + P(11, 20) * _tmp10 + - P(12, 20) * _tmp9 + P(2, 20) * _tmp5 + P(3, 20) * _tmp2; - _p_new(1, 20) = P(0, 20) * _tmp33 + P(1, 20) - P(10, 20) * _tmp30 + P(11, 20) * _tmp9 - - P(12, 20) * _tmp10 + P(2, 20) * _tmp32 + P(3, 20) * _tmp5; - _p_new(2, 20) = P(0, 20) * _tmp43 + P(1, 20) * _tmp2 - P(10, 20) * _tmp9 - P(11, 20) * _tmp30 + - P(12, 20) * _tmp11 + P(2, 20) + P(3, 20) * _tmp33; - _p_new(3, 20) = P(0, 20) * _tmp32 + P(1, 20) * _tmp43 + P(10, 20) * _tmp10 - - P(11, 20) * _tmp11 - P(12, 20) * _tmp30 + P(2, 20) * _tmp8 + P(3, 20); - _p_new(4, 20) = P(0, 20) * _tmp68 + P(1, 20) * _tmp65 - P(13, 20) * _tmp86 - - P(14, 20) * _tmp82 - P(15, 20) * _tmp78 + P(2, 20) * _tmp91 + - P(3, 20) * _tmp75 + P(4, 20); - _p_new(5, 20) = P(0, 20) * _tmp118 + P(1, 20) * _tmp129 - P(13, 20) * _tmp121 - - P(14, 20) * _tmp126 - P(15, 20) * _tmp124 + P(2, 20) * _tmp116 + - P(3, 20) * _tmp120 + P(5, 20); - _p_new(6, 20) = P(0, 20) * _tmp148 + P(1, 20) * _tmp150 - P(13, 20) * _tmp151 - - P(14, 20) * _tmp152 - P(15, 20) * _tmp153 + P(2, 20) * _tmp149 + - P(3, 20) * _tmp147 + P(6, 20); + _p_new(0, 20) = P(0, 20) + P(1, 20) * _tmp3 + P(10, 20) * _tmp12 + P(11, 20) * _tmp10 + + P(12, 20) * _tmp11 + P(2, 20) * _tmp9 + P(3, 20) * _tmp6; + _p_new(1, 20) = P(0, 20) * _tmp30 + P(1, 20) - P(10, 20) * _tmp29 + P(11, 20) * _tmp11 - + P(12, 20) * _tmp10 + P(2, 20) * _tmp31 + P(3, 20) * _tmp9; + _p_new(2, 20) = P(0, 20) * _tmp41 + P(1, 20) * _tmp6 - P(10, 20) * _tmp11 - P(11, 20) * _tmp29 + + P(12, 20) * _tmp12 + P(2, 20) + P(3, 20) * _tmp30; + _p_new(3, 20) = P(0, 20) * _tmp31 + P(1, 20) * _tmp41 + P(10, 20) * _tmp10 - + P(11, 20) * _tmp12 - P(12, 20) * _tmp29 + P(2, 20) * _tmp3 + P(3, 20); + _p_new(4, 20) = P(0, 20) * _tmp80 + P(1, 20) * _tmp83 - P(13, 20) * _tmp61 - + P(14, 20) * _tmp73 - P(15, 20) * _tmp68 + P(2, 20) * _tmp91 + + P(3, 20) * _tmp88 + P(4, 20); + _p_new(5, 20) = P(0, 20) * _tmp123 + P(1, 20) * _tmp126 - P(13, 20) * _tmp119 - + P(14, 20) * _tmp117 - P(15, 20) * _tmp132 + P(2, 20) * _tmp121 + + P(3, 20) * _tmp128 + P(5, 20); + _p_new(6, 20) = P(0, 20) * _tmp154 + P(1, 20) * _tmp157 - P(13, 20) * _tmp153 - + P(14, 20) * _tmp160 - P(15, 20) * _tmp151 + P(2, 20) * _tmp158 + + P(3, 20) * _tmp155 + P(6, 20); _p_new(7, 20) = P(4, 20) * dt + P(7, 20); _p_new(8, 20) = P(5, 20) * dt + P(8, 20); _p_new(9, 20) = P(6, 20) * dt + P(9, 20); @@ -966,23 +968,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 20) = 0; _p_new(22, 20) = 0; _p_new(23, 20) = 0; - _p_new(0, 21) = P(0, 21) + P(1, 21) * _tmp8 + P(10, 21) * _tmp11 + P(11, 21) * _tmp10 + - P(12, 21) * _tmp9 + P(2, 21) * _tmp5 + P(3, 21) * _tmp2; - _p_new(1, 21) = P(0, 21) * _tmp33 + P(1, 21) - P(10, 21) * _tmp30 + P(11, 21) * _tmp9 - - P(12, 21) * _tmp10 + P(2, 21) * _tmp32 + P(3, 21) * _tmp5; - _p_new(2, 21) = P(0, 21) * _tmp43 + P(1, 21) * _tmp2 - P(10, 21) * _tmp9 - P(11, 21) * _tmp30 + - P(12, 21) * _tmp11 + P(2, 21) + P(3, 21) * _tmp33; - _p_new(3, 21) = P(0, 21) * _tmp32 + P(1, 21) * _tmp43 + P(10, 21) * _tmp10 - - P(11, 21) * _tmp11 - P(12, 21) * _tmp30 + P(2, 21) * _tmp8 + P(3, 21); - _p_new(4, 21) = P(0, 21) * _tmp68 + P(1, 21) * _tmp65 - P(13, 21) * _tmp86 - - P(14, 21) * _tmp82 - P(15, 21) * _tmp78 + P(2, 21) * _tmp91 + - P(3, 21) * _tmp75 + P(4, 21); - _p_new(5, 21) = P(0, 21) * _tmp118 + P(1, 21) * _tmp129 - P(13, 21) * _tmp121 - - P(14, 21) * _tmp126 - P(15, 21) * _tmp124 + P(2, 21) * _tmp116 + - P(3, 21) * _tmp120 + P(5, 21); - _p_new(6, 21) = P(0, 21) * _tmp148 + P(1, 21) * _tmp150 - P(13, 21) * _tmp151 - - P(14, 21) * _tmp152 - P(15, 21) * _tmp153 + P(2, 21) * _tmp149 + - P(3, 21) * _tmp147 + P(6, 21); + _p_new(0, 21) = P(0, 21) + P(1, 21) * _tmp3 + P(10, 21) * _tmp12 + P(11, 21) * _tmp10 + + P(12, 21) * _tmp11 + P(2, 21) * _tmp9 + P(3, 21) * _tmp6; + _p_new(1, 21) = P(0, 21) * _tmp30 + P(1, 21) - P(10, 21) * _tmp29 + P(11, 21) * _tmp11 - + P(12, 21) * _tmp10 + P(2, 21) * _tmp31 + P(3, 21) * _tmp9; + _p_new(2, 21) = P(0, 21) * _tmp41 + P(1, 21) * _tmp6 - P(10, 21) * _tmp11 - P(11, 21) * _tmp29 + + P(12, 21) * _tmp12 + P(2, 21) + P(3, 21) * _tmp30; + _p_new(3, 21) = P(0, 21) * _tmp31 + P(1, 21) * _tmp41 + P(10, 21) * _tmp10 - + P(11, 21) * _tmp12 - P(12, 21) * _tmp29 + P(2, 21) * _tmp3 + P(3, 21); + _p_new(4, 21) = P(0, 21) * _tmp80 + P(1, 21) * _tmp83 - P(13, 21) * _tmp61 - + P(14, 21) * _tmp73 - P(15, 21) * _tmp68 + P(2, 21) * _tmp91 + + P(3, 21) * _tmp88 + P(4, 21); + _p_new(5, 21) = P(0, 21) * _tmp123 + P(1, 21) * _tmp126 - P(13, 21) * _tmp119 - + P(14, 21) * _tmp117 - P(15, 21) * _tmp132 + P(2, 21) * _tmp121 + + P(3, 21) * _tmp128 + P(5, 21); + _p_new(6, 21) = P(0, 21) * _tmp154 + P(1, 21) * _tmp157 - P(13, 21) * _tmp153 - + P(14, 21) * _tmp160 - P(15, 21) * _tmp151 + P(2, 21) * _tmp158 + + P(3, 21) * _tmp155 + P(6, 21); _p_new(7, 21) = P(4, 21) * dt + P(7, 21); _p_new(8, 21) = P(5, 21) * dt + P(8, 21); _p_new(9, 21) = P(6, 21) * dt + P(9, 21); @@ -1000,23 +1002,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 21) = P(21, 21); _p_new(22, 21) = 0; _p_new(23, 21) = 0; - _p_new(0, 22) = P(0, 22) + P(1, 22) * _tmp8 + P(10, 22) * _tmp11 + P(11, 22) * _tmp10 + - P(12, 22) * _tmp9 + P(2, 22) * _tmp5 + P(3, 22) * _tmp2; - _p_new(1, 22) = P(0, 22) * _tmp33 + P(1, 22) - P(10, 22) * _tmp30 + P(11, 22) * _tmp9 - - P(12, 22) * _tmp10 + P(2, 22) * _tmp32 + P(3, 22) * _tmp5; - _p_new(2, 22) = P(0, 22) * _tmp43 + P(1, 22) * _tmp2 - P(10, 22) * _tmp9 - P(11, 22) * _tmp30 + - P(12, 22) * _tmp11 + P(2, 22) + P(3, 22) * _tmp33; - _p_new(3, 22) = P(0, 22) * _tmp32 + P(1, 22) * _tmp43 + P(10, 22) * _tmp10 - - P(11, 22) * _tmp11 - P(12, 22) * _tmp30 + P(2, 22) * _tmp8 + P(3, 22); - _p_new(4, 22) = P(0, 22) * _tmp68 + P(1, 22) * _tmp65 - P(13, 22) * _tmp86 - - P(14, 22) * _tmp82 - P(15, 22) * _tmp78 + P(2, 22) * _tmp91 + - P(3, 22) * _tmp75 + P(4, 22); - _p_new(5, 22) = P(0, 22) * _tmp118 + P(1, 22) * _tmp129 - P(13, 22) * _tmp121 - - P(14, 22) * _tmp126 - P(15, 22) * _tmp124 + P(2, 22) * _tmp116 + - P(3, 22) * _tmp120 + P(5, 22); - _p_new(6, 22) = P(0, 22) * _tmp148 + P(1, 22) * _tmp150 - P(13, 22) * _tmp151 - - P(14, 22) * _tmp152 - P(15, 22) * _tmp153 + P(2, 22) * _tmp149 + - P(3, 22) * _tmp147 + P(6, 22); + _p_new(0, 22) = P(0, 22) + P(1, 22) * _tmp3 + P(10, 22) * _tmp12 + P(11, 22) * _tmp10 + + P(12, 22) * _tmp11 + P(2, 22) * _tmp9 + P(3, 22) * _tmp6; + _p_new(1, 22) = P(0, 22) * _tmp30 + P(1, 22) - P(10, 22) * _tmp29 + P(11, 22) * _tmp11 - + P(12, 22) * _tmp10 + P(2, 22) * _tmp31 + P(3, 22) * _tmp9; + _p_new(2, 22) = P(0, 22) * _tmp41 + P(1, 22) * _tmp6 - P(10, 22) * _tmp11 - P(11, 22) * _tmp29 + + P(12, 22) * _tmp12 + P(2, 22) + P(3, 22) * _tmp30; + _p_new(3, 22) = P(0, 22) * _tmp31 + P(1, 22) * _tmp41 + P(10, 22) * _tmp10 - + P(11, 22) * _tmp12 - P(12, 22) * _tmp29 + P(2, 22) * _tmp3 + P(3, 22); + _p_new(4, 22) = P(0, 22) * _tmp80 + P(1, 22) * _tmp83 - P(13, 22) * _tmp61 - + P(14, 22) * _tmp73 - P(15, 22) * _tmp68 + P(2, 22) * _tmp91 + + P(3, 22) * _tmp88 + P(4, 22); + _p_new(5, 22) = P(0, 22) * _tmp123 + P(1, 22) * _tmp126 - P(13, 22) * _tmp119 - + P(14, 22) * _tmp117 - P(15, 22) * _tmp132 + P(2, 22) * _tmp121 + + P(3, 22) * _tmp128 + P(5, 22); + _p_new(6, 22) = P(0, 22) * _tmp154 + P(1, 22) * _tmp157 - P(13, 22) * _tmp153 - + P(14, 22) * _tmp160 - P(15, 22) * _tmp151 + P(2, 22) * _tmp158 + + P(3, 22) * _tmp155 + P(6, 22); _p_new(7, 22) = P(4, 22) * dt + P(7, 22); _p_new(8, 22) = P(5, 22) * dt + P(8, 22); _p_new(9, 22) = P(6, 22) * dt + P(9, 22); @@ -1034,23 +1036,23 @@ void PredictCovariance(const matrix::Matrix& state, _p_new(21, 22) = P(21, 22); _p_new(22, 22) = P(22, 22); _p_new(23, 22) = 0; - _p_new(0, 23) = P(0, 23) + P(1, 23) * _tmp8 + P(10, 23) * _tmp11 + P(11, 23) * _tmp10 + - P(12, 23) * _tmp9 + P(2, 23) * _tmp5 + P(3, 23) * _tmp2; - _p_new(1, 23) = P(0, 23) * _tmp33 + P(1, 23) - P(10, 23) * _tmp30 + P(11, 23) * _tmp9 - - P(12, 23) * _tmp10 + P(2, 23) * _tmp32 + P(3, 23) * _tmp5; - _p_new(2, 23) = P(0, 23) * _tmp43 + P(1, 23) * _tmp2 - P(10, 23) * _tmp9 - P(11, 23) * _tmp30 + - P(12, 23) * _tmp11 + P(2, 23) + P(3, 23) * _tmp33; - _p_new(3, 23) = P(0, 23) * _tmp32 + P(1, 23) * _tmp43 + P(10, 23) * _tmp10 - - P(11, 23) * _tmp11 - P(12, 23) * _tmp30 + P(2, 23) * _tmp8 + P(3, 23); - _p_new(4, 23) = P(0, 23) * _tmp68 + P(1, 23) * _tmp65 - P(13, 23) * _tmp86 - - P(14, 23) * _tmp82 - P(15, 23) * _tmp78 + P(2, 23) * _tmp91 + - P(3, 23) * _tmp75 + P(4, 23); - _p_new(5, 23) = P(0, 23) * _tmp118 + P(1, 23) * _tmp129 - P(13, 23) * _tmp121 - - P(14, 23) * _tmp126 - P(15, 23) * _tmp124 + P(2, 23) * _tmp116 + - P(3, 23) * _tmp120 + P(5, 23); - _p_new(6, 23) = P(0, 23) * _tmp148 + P(1, 23) * _tmp150 - P(13, 23) * _tmp151 - - P(14, 23) * _tmp152 - P(15, 23) * _tmp153 + P(2, 23) * _tmp149 + - P(3, 23) * _tmp147 + P(6, 23); + _p_new(0, 23) = P(0, 23) + P(1, 23) * _tmp3 + P(10, 23) * _tmp12 + P(11, 23) * _tmp10 + + P(12, 23) * _tmp11 + P(2, 23) * _tmp9 + P(3, 23) * _tmp6; + _p_new(1, 23) = P(0, 23) * _tmp30 + P(1, 23) - P(10, 23) * _tmp29 + P(11, 23) * _tmp11 - + P(12, 23) * _tmp10 + P(2, 23) * _tmp31 + P(3, 23) * _tmp9; + _p_new(2, 23) = P(0, 23) * _tmp41 + P(1, 23) * _tmp6 - P(10, 23) * _tmp11 - P(11, 23) * _tmp29 + + P(12, 23) * _tmp12 + P(2, 23) + P(3, 23) * _tmp30; + _p_new(3, 23) = P(0, 23) * _tmp31 + P(1, 23) * _tmp41 + P(10, 23) * _tmp10 - + P(11, 23) * _tmp12 - P(12, 23) * _tmp29 + P(2, 23) * _tmp3 + P(3, 23); + _p_new(4, 23) = P(0, 23) * _tmp80 + P(1, 23) * _tmp83 - P(13, 23) * _tmp61 - + P(14, 23) * _tmp73 - P(15, 23) * _tmp68 + P(2, 23) * _tmp91 + + P(3, 23) * _tmp88 + P(4, 23); + _p_new(5, 23) = P(0, 23) * _tmp123 + P(1, 23) * _tmp126 - P(13, 23) * _tmp119 - + P(14, 23) * _tmp117 - P(15, 23) * _tmp132 + P(2, 23) * _tmp121 + + P(3, 23) * _tmp128 + P(5, 23); + _p_new(6, 23) = P(0, 23) * _tmp154 + P(1, 23) * _tmp157 - P(13, 23) * _tmp153 - + P(14, 23) * _tmp160 - P(15, 23) * _tmp151 + P(2, 23) * _tmp158 + + P(3, 23) * _tmp155 + P(6, 23); _p_new(7, 23) = P(4, 23) * dt + P(7, 23); _p_new(8, 23) = P(5, 23) * dt + P(8, 23); _p_new(9, 23) = P(6, 23) * dt + P(9, 23); diff --git a/src/modules/ekf2/EKF/utils.hpp b/src/modules/ekf2/EKF/utils.hpp deleted file mode 100644 index 4d911f6e20..0000000000 --- a/src/modules/ekf2/EKF/utils.hpp +++ /dev/null @@ -1,75 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2020-2022 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 - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include - -#ifndef EKF_UTILS_HPP -#define EKF_UTILS_HPP - -// Use Kahan summation algorithm to get the sum of "sum_previous" and "input". -// This function relies on the caller to be responsible for keeping a copy of -// "accumulator" and passing this value at the next iteration. -// Ref: https://en.wikipedia.org/wiki/Kahan_summation_algorithm -inline float kahanSummation(float sum_previous, float input, float &accumulator) -{ - const float y = input - accumulator; - const float t = sum_previous + y; - accumulator = (t - sum_previous) - y; - return t; -} - -namespace ecl -{ -inline float powf(float x, int exp) -{ - float ret; - - if (exp > 0) { - ret = x; - - for (int count = 1; count < exp; count++) { - ret *= x; - } - - return ret; - - } else if (exp < 0) { - return 1.0f / ecl::powf(x, -exp); - } - - return 1.0f; -} - -} // namespace ecl - -#endif // EKF_UTILS_HPP diff --git a/src/modules/ekf2/EKF/zero_gyro_update.cpp b/src/modules/ekf2/EKF/zero_gyro_update.cpp index 7a74ee2517..51551fec93 100644 --- a/src/modules/ekf2/EKF/zero_gyro_update.cpp +++ b/src/modules/ekf2/EKF/zero_gyro_update.cpp @@ -54,12 +54,10 @@ void Ekf::controlZeroGyroUpdate(const imuSample &imu_delayed) const bool zero_gyro_update_data_ready = _zgup_delta_ang_dt >= zgup_dt; if (zero_gyro_update_data_ready) { - Vector3f delta_ang_scaled = _zgup_delta_ang / _zgup_delta_ang_dt * _dt_ekf_avg; - Vector3f innovation = _state.delta_ang_bias - delta_ang_scaled; + Vector3f gyro_bias = _zgup_delta_ang / _zgup_delta_ang_dt; + Vector3f innovation = _state.gyro_bias - gyro_bias; - const float d_ang_sig = _dt_ekf_avg * math::constrain(_params.gyro_noise, 0.0f, 1.0f); - //const float obs_var = sq(d_ang_sig) * (_dt_ekf_avg / _zgup_delta_ang_dt); // This is correct but too small for single precision - const float obs_var = sq(d_ang_sig); + const float obs_var = sq(math::constrain(_params.gyro_noise, 0.f, 1.f)); Vector3f innov_var{ P(10, 10) + obs_var, diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index e7605af86b..4412be2fa3 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -40,7 +40,6 @@ px4_add_unit_gtest(SRC test_EKF_accelerometer.cpp LINKLIBS ecl_EKF ecl_sensor_si px4_add_unit_gtest(SRC test_EKF_airspeed_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_covariance_prediction_generated.cpp LINKLIBS ecl_EKF ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_flow.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gyroscope.cpp LINKLIBS ecl_EKF ecl_sensor_sim) 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 32b122a5ee..01ec200577 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -1,391 +1,391 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,4.9e-07,0.0025,0.0025,0.005,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -90000,1,-0.0096,-0.01,-0.02,-0.0004,0.0026,-0.026,-1.4e-05,0.00011,-0.0023,0,0,0,0,0,0,0.19,-9.3e-10,0.4,0,0,0,0,0,5.2e-07,0.0026,0.0026,0.0051,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -190000,1,-0.0096,-0.011,-0.02,0.0002,0.0039,-0.041,6e-06,0.00043,-0.0044,-3e-13,-2.3e-14,4.9e-15,0,0,-2e-11,0.19,-9.3e-10,0.4,0,0,0,0,0,5.8e-07,0.0027,0.0027,0.0052,25,25,10,1e+02,1e+02,1,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -290000,1,-0.0097,-0.011,-0.02,0.0012,0.0063,-0.053,5e-05,0.00036,-0.007,9.1e-12,9.1e-13,-2.1e-13,0,0,-4.8e-09,0.19,-9.3e-10,0.4,0,0,0,0,0,6.8e-07,0.0029,0.0029,0.0054,25,25,9.6,0.37,0.37,0.41,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -390000,1,-0.0089,-0.012,0.046,0.0026,0.0083,-0.059,0.00024,0.0011,-0.0094,-1.1e-10,2.8e-11,2.7e-12,0,0,-4.5e-08,0.17,0.0017,0.41,0,0,0,0,0,7e-07,0.0031,0.0031,0.0056,25,25,8.1,0.97,0.97,0.32,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -490000,0.87,-0.0023,-0.015,0.5,0.0023,0.0057,-0.06,0.0002,0.00051,-0.011,1.6e-08,-3.8e-09,-4.1e-10,0,0,-1.6e-07,0.14,0.0014,0.42,0,0,0,0,0,2.9e-06,0.0033,0.0033,0.0058,7.8,7.8,5.9,0.34,0.34,0.31,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -590000,0.76,0.00067,-0.015,0.65,0.00071,0.0084,-0.059,0.00037,0.0012,-0.012,1.6e-08,-3.5e-09,-3.8e-10,0,0,-3.4e-07,0.18,0.0018,0.43,0,0,0,0,0,1.9e-05,0.0036,0.0036,0.0061,7.9,7.9,4.2,0.67,0.67,0.32,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -690000,0.72,0.0016,-0.016,0.69,-0.00082,0.0075,-0.06,7.2e-05,0.00069,-0.013,5.4e-08,-2.4e-08,-1.7e-09,0,0,-6.3e-07,0.2,0.002,0.43,0,0,0,0,0,5.9e-05,0.0039,0.0039,0.0064,2.6,2.6,2.8,0.26,0.26,0.29,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -790000,0.71,0.002,-0.016,0.7,-0.0028,0.0098,-0.063,-9.3e-05,0.0015,-0.014,5.3e-08,-2.3e-08,-1.6e-09,0,0,-9.5e-07,0.2,0.002,0.43,0,0,0,0,0,0.00012,0.0042,0.0042,0.0066,2.7,2.7,2,0.42,0.42,0.28,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -890000,0.71,0.0021,-0.016,0.7,-0.0034,0.011,-0.077,-0.00019,0.0011,-0.021,1.7e-07,-9e-08,-6.6e-09,0,0,-9.5e-07,0.2,0.002,0.43,0,0,0,0,0,0.00021,0.0046,0.0046,0.0069,1.3,1.3,2,0.2,0.2,0.43,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -990000,0.7,0.0025,-0.016,0.71,-0.0038,0.015,-0.092,-0.00057,0.0024,-0.029,1.7e-07,-9e-08,-6.6e-09,0,0,-9.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00033,0.005,0.005,0.0073,1.4,1.4,2,0.3,0.3,0.61,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1090000,0.7,0.0025,-0.017,0.71,-0.0034,0.016,-0.11,-0.00043,0.0019,-0.039,5.5e-07,-3.7e-07,-2.5e-08,0,0,-9.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00047,0.0053,0.0053,0.0076,0.89,0.89,2,0.17,0.17,0.84,9.9e-07,9.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1190000,0.7,0.0027,-0.017,0.71,-0.0037,0.02,-0.12,-0.00079,0.0037,-0.051,5.5e-07,-3.7e-07,-2.5e-08,0,0,-9.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00064,0.0058,0.0058,0.008,1.1,1.1,2,0.24,0.24,1.1,9.9e-07,9.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1290000,0.7,0.0028,-0.017,0.71,-0.0034,0.02,-0.14,-0.00055,0.0028,-0.064,1.4e-06,-1.3e-06,-7.3e-08,0,0,-9.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.00083,0.006,0.006,0.0084,0.84,0.84,2,0.15,0.15,1.4,9.6e-07,9.6e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1390000,0.7,0.0029,-0.017,0.71,-0.0032,0.026,-0.15,-0.0009,0.0052,-0.078,1.4e-06,-1.3e-06,-7.3e-08,0,0,-9.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.001,0.0066,0.0066,0.0088,1.1,1.1,2,0.21,0.21,1.7,9.6e-07,9.6e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1490000,0.7,0.0027,-0.017,0.71,-0.0024,0.025,-0.16,-0.0006,0.0039,-0.093,2.9e-06,-3.4e-06,-1.7e-07,0,0,-9.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.0013,0.0063,0.0063,0.0093,0.9,0.9,2,0.14,0.14,2.1,9e-07,9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1590000,0.7,0.0029,-0.018,0.71,-0.0029,0.031,-0.18,-0.00087,0.0066,-0.11,2.9e-06,-3.4e-06,-1.7e-07,0,0,-9.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.0016,0.0069,0.0069,0.0097,1.2,1.2,2,0.2,0.2,2.6,9e-07,9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1690000,0.7,0.0025,-0.018,0.71,0.00055,0.028,-0.19,-0.00048,0.0047,-0.13,5e-06,-7e-06,-3.1e-07,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0018,0.0061,0.006,0.01,0.97,0.97,2,0.13,0.13,3,8.1e-07,8.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1790000,0.7,0.0027,-0.018,0.71,0.0025,0.036,-0.2,-0.00035,0.0078,-0.15,5e-06,-7e-06,-3.1e-07,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0022,0.0066,0.0066,0.011,1.3,1.3,2,0.2,0.2,3.5,8.1e-07,8.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1890000,0.7,0.003,-0.018,0.72,0.0038,0.044,-0.22,-2.9e-05,0.012,-0.17,5e-06,-7e-06,-3.1e-07,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0025,0.0073,0.0073,0.011,1.6,1.6,2,0.3,0.3,4.1,8.1e-07,8.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1990000,0.7,0.0025,-0.018,0.72,0.0056,0.037,-0.23,0.00047,0.0085,-0.19,6.8e-06,-1.2e-05,-4.8e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0029,0.0059,0.0059,0.012,1.3,1.3,2,0.2,0.2,4.7,7e-07,7e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2090000,0.7,0.0026,-0.018,0.72,0.0083,0.043,-0.24,0.0012,0.012,-0.22,6.8e-06,-1.2e-05,-4.8e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0033,0.0064,0.0064,0.012,1.6,1.6,2.1,0.3,0.3,5.3,7e-07,7e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2190000,0.7,0.0021,-0.018,0.72,0.0084,0.034,-0.26,0.0012,0.0083,-0.24,8e-06,-1.8e-05,-6.3e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0037,0.0049,0.0049,0.013,1.2,1.2,2.1,0.19,0.19,6,5.8e-07,5.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2290000,0.7,0.0021,-0.018,0.72,0.011,0.041,-0.27,0.0022,0.012,-0.27,8e-06,-1.8e-05,-6.3e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0041,0.0054,0.0054,0.014,1.5,1.5,2.1,0.29,0.29,6.7,5.8e-07,5.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2390000,0.7,0.0016,-0.017,0.72,0.011,0.031,-0.29,0.0019,0.0078,-0.3,8.3e-06,-2.4e-05,-7.6e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0046,0.004,0.004,0.014,1,1,2.1,0.19,0.19,7.4,4.9e-07,4.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2490000,0.7,0.0017,-0.018,0.72,0.014,0.036,-0.3,0.0031,0.011,-0.32,8.3e-06,-2.4e-05,-7.6e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0051,0.0044,0.0044,0.015,1.3,1.3,2.1,0.27,0.27,8.2,4.9e-07,4.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2590000,0.7,0.0014,-0.017,0.72,0.012,0.027,-0.31,0.0023,0.0071,-0.36,8e-06,-2.8e-05,-8.4e-07,0,0,-1.2e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0056,0.0033,0.0033,0.016,0.89,0.89,2.1,0.18,0.18,9.1,4.1e-07,4.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2690000,0.7,0.0014,-0.017,0.72,0.015,0.031,-0.33,0.0037,0.01,-0.39,8e-06,-2.8e-05,-8.4e-07,0,0,-1.2e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0062,0.0036,0.0036,0.016,1.1,1.1,2.2,0.25,0.25,10,4.1e-07,4.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2790000,0.7,0.0012,-0.017,0.72,0.014,0.024,-0.34,0.0027,0.0064,-0.42,7.1e-06,-3.3e-05,-9e-07,0,0,-1.2e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0068,0.0028,0.0028,0.017,0.77,0.77,2.2,0.16,0.16,11,3.4e-07,3.4e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2890000,0.7,0.0012,-0.017,0.72,0.016,0.027,-0.35,0.0041,0.0089,-0.46,7.1e-06,-3.3e-05,-9e-07,0,0,-1.2e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0074,0.0031,0.003,0.018,0.96,0.96,2.2,0.23,0.23,12,3.4e-07,3.4e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -2990000,0.7,0.0011,-0.017,0.72,0.014,0.022,-0.36,0.003,0.0058,-0.49,6e-06,-3.6e-05,-9.4e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.008,0.0024,0.0024,0.019,0.68,0.68,2.2,0.15,0.15,13,2.9e-07,2.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3090000,0.7,0.0011,-0.017,0.72,0.017,0.024,-0.38,0.0045,0.0081,-0.53,6e-06,-3.6e-05,-9.4e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0087,0.0026,0.0026,0.02,0.84,0.84,2.2,0.22,0.22,14,2.9e-07,2.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3190000,0.7,0.0009,-0.017,0.72,0.014,0.019,-0.39,0.0032,0.0053,-0.57,4.6e-06,-3.9e-05,-9.6e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.0093,0.0021,0.0021,0.021,0.6,0.6,2.3,0.14,0.14,15,2.5e-07,2.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3290000,0.7,0.00089,-0.017,0.72,0.017,0.023,-0.4,0.0047,0.0074,-0.61,4.6e-06,-3.9e-05,-9.6e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.01,0.0023,0.0023,0.021,0.74,0.74,2.3,0.2,0.2,16,2.5e-07,2.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3390000,0.7,0.00085,-0.017,0.72,0.015,0.018,-0.42,0.0033,0.0049,-0.65,3.1e-06,-4.2e-05,-9.7e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.011,0.0018,0.0018,0.022,0.54,0.54,2.3,0.14,0.14,17,2.1e-07,2.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3490000,0.7,0.00086,-0.017,0.72,0.019,0.021,-0.43,0.005,0.0068,-0.69,3.1e-06,-4.2e-05,-9.7e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.012,0.002,0.002,0.023,0.67,0.67,2.3,0.19,0.19,19,2.1e-07,2.1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3590000,0.7,0.00079,-0.017,0.72,0.017,0.016,-0.44,0.0036,0.0045,-0.73,1.5e-06,-4.4e-05,-9.7e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.012,0.0016,0.0016,0.024,0.5,0.5,2.4,0.13,0.13,20,1.8e-07,1.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3690000,0.7,0.00079,-0.017,0.72,0.021,0.018,-0.46,0.0055,0.0063,-0.78,1.5e-06,-4.4e-05,-9.7e-07,0,0,-1.1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.013,0.0018,0.0018,0.025,0.61,0.61,2.4,0.18,0.18,21,1.8e-07,1.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3790000,0.7,0.00073,-0.017,0.72,0.02,0.014,-0.47,0.004,0.0042,-0.83,-3.1e-07,-4.6e-05,-9.5e-07,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.014,0.0015,0.0014,0.026,0.46,0.46,2.4,0.12,0.12,23,1.5e-07,1.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3890000,0.7,0.00077,-0.017,0.72,0.022,0.016,-0.48,0.0061,0.0057,-0.87,-3.1e-07,-4.6e-05,-9.5e-07,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.015,0.0016,0.0016,0.027,0.56,0.56,2.4,0.17,0.17,24,1.5e-07,1.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -3990000,0.7,0.00081,-0.017,0.72,0.025,0.019,-0.5,0.0084,0.0074,-0.92,-3.1e-07,-4.6e-05,-9.5e-07,0,0,-1e-06,0.21,0.0021,0.43,0,0,0,0,0,0.016,0.0018,0.0017,0.028,0.68,0.68,2.5,0.23,0.23,26,1.5e-07,1.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4090000,0.7,0.00079,-0.016,0.72,0.021,0.016,-0.51,0.0062,0.0053,-0.97,-2.2e-06,-4.8e-05,-9.3e-07,0,0,-9.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.017,0.0014,0.0014,0.029,0.52,0.52,2.5,0.16,0.16,27,1.2e-07,1.2e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4190000,0.7,0.00077,-0.016,0.72,0.025,0.018,-0.53,0.0086,0.007,-1,-2.2e-06,-4.8e-05,-9.3e-07,0,0,-9.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.018,0.0016,0.0015,0.03,0.63,0.63,2.5,0.22,0.22,29,1.2e-07,1.2e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4290000,0.7,0.0008,-0.016,0.72,0.019,0.015,-0.54,0.0063,0.005,-1.1,-4.1e-06,-5e-05,-9e-07,0,0,-9.3e-07,0.21,0.0021,0.43,0,0,0,0,0,0.018,0.0013,0.0012,0.032,0.48,0.48,2.6,0.15,0.15,31,1e-07,1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4390000,0.7,0.00068,-0.016,0.71,0.021,0.016,-0.55,0.0083,0.0066,-1.1,-4.1e-06,-5e-05,-9e-07,0,0,-9.3e-07,0.21,0.0021,0.43,0,0,0,0,0,0.019,0.0014,0.0014,0.033,0.58,0.58,2.6,0.2,0.2,33,1e-07,1e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4490000,0.7,0.00073,-0.016,0.71,0.017,0.013,-0.57,0.0058,0.0046,-1.2,-5.9e-06,-5.1e-05,-8.8e-07,0,0,-8.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.02,0.0011,0.0011,0.034,0.44,0.44,2.6,0.14,0.14,34,8.3e-08,8.3e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4590000,0.7,0.00069,-0.016,0.71,0.019,0.015,-0.58,0.0076,0.006,-1.2,-5.9e-06,-5.1e-05,-8.8e-07,0,0,-8.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.022,0.0012,0.0012,0.035,0.53,0.53,2.7,0.19,0.19,36,8.3e-08,8.3e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4690000,0.7,0.0007,-0.016,0.71,0.016,0.012,-0.6,0.0054,0.0043,-1.3,-7.4e-06,-5.2e-05,-8.6e-07,0,0,-8.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.023,0.00097,0.00095,0.036,0.41,0.41,2.7,0.14,0.14,38,6.8e-08,6.8e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4790000,0.7,0.00063,-0.016,0.71,0.018,0.014,-0.61,0.0071,0.0056,-1.4,-7.4e-06,-5.2e-05,-8.6e-07,0,0,-8.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.024,0.0011,0.001,0.038,0.49,0.49,2.7,0.18,0.18,40,6.8e-08,6.8e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4890000,0.7,0.00065,-0.016,0.71,0.016,0.011,-0.63,0.0051,0.0039,-1.4,-8.8e-06,-5.3e-05,-8.4e-07,0,0,-7.9e-07,0.21,0.0021,0.43,0,0,0,0,0,0.025,0.00085,0.00083,0.039,0.37,0.37,2.8,0.13,0.13,42,5.5e-08,5.5e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -4990000,0.7,0.00068,-0.016,0.71,0.017,0.013,-0.64,0.0068,0.0051,-1.5,-8.8e-06,-5.3e-05,-8.4e-07,0,0,-7.9e-07,0.21,0.0021,0.43,0,0,0,0,0,0.026,0.00092,0.00089,0.04,0.44,0.44,2.8,0.17,0.17,44,5.5e-08,5.5e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5090000,0.7,0.00069,-0.015,0.71,0.014,0.01,-0.66,0.0049,0.0036,-1.6,-1e-05,-5.4e-05,-8.3e-07,0,0,-7.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.027,0.00074,0.00071,0.042,0.34,0.34,2.8,0.13,0.13,46,4.4e-08,4.4e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5190000,0.7,0.00068,-0.015,0.71,0.016,0.011,-0.67,0.0064,0.0047,-1.6,-1e-05,-5.4e-05,-8.3e-07,0,0,-7.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.028,0.00079,0.00077,0.043,0.4,0.4,2.9,0.16,0.16,49,4.4e-08,4.4e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5290000,0.7,0.00075,-0.015,0.71,0.012,0.0072,-0.68,0.0046,0.0033,-1.7,-1.1e-05,-5.5e-05,-8.2e-07,0,0,-7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.029,0.00064,0.00062,0.044,0.31,0.31,2.9,0.12,0.12,51,3.6e-08,3.6e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5390000,0.7,0.00084,-0.015,0.71,0.014,0.0066,-0.7,0.0058,0.0039,-1.8,-1.1e-05,-5.5e-05,-8.2e-07,0,0,-7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.031,0.00068,0.00066,0.046,0.37,0.37,2.9,0.16,0.16,53,3.6e-08,3.6e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5490000,0.7,0.00091,-0.015,0.71,0.011,0.0042,-0.71,0.0042,0.0026,-1.8,-1.2e-05,-5.5e-05,-8.1e-07,0,0,-6.7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.032,0.00055,0.00053,0.047,0.28,0.28,3,0.11,0.11,56,2.9e-08,2.9e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5590000,0.7,0.00092,-0.015,0.71,0.012,0.0047,-0.73,0.0053,0.003,-1.9,-1.2e-05,-5.5e-05,-8.1e-07,0,0,-6.7e-07,0.21,0.0021,0.43,0,0,0,0,0,0.033,0.00059,0.00057,0.049,0.33,0.33,3,0.15,0.15,58,2.9e-08,2.9e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5690000,0.7,0.001,-0.015,0.71,0.0081,0.003,-0.74,0.0037,0.002,-2,-1.3e-05,-5.6e-05,-8e-07,0,0,-6.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.035,0.00048,0.00046,0.05,0.26,0.26,3.1,0.11,0.11,61,2.3e-08,2.3e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5790000,0.7,0.0011,-0.015,0.71,0.0074,0.0032,-0.75,0.0045,0.0023,-2.1,-1.3e-05,-5.6e-05,-8e-07,0,0,-6.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.036,0.00051,0.00049,0.052,0.3,0.3,3.1,0.14,0.14,64,2.3e-08,2.3e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5890000,0.7,0.0011,-0.015,0.71,0.0048,0.0028,0.0028,0.003,0.0016,-3.7e+02,-1.3e-05,-5.6e-05,-7.9e-07,0,0,-6.4e-07,0.21,0.0021,0.43,0,0,0,0,0,0.037,0.00042,0.00039,0.053,0.23,0.23,9.8,0.11,0.11,0.52,1.9e-08,1.9e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -5990000,0.7,0.0011,-0.015,0.71,0.0037,0.0029,0.015,0.0034,0.0018,-3.7e+02,-1.3e-05,-5.6e-05,-7.9e-07,0,0,-7.3e-07,0.21,0.0021,0.43,0,0,0,0,0,0.039,0.00044,0.00042,0.055,0.27,0.27,8.8,0.13,0.13,0.33,1.9e-08,1.9e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6090000,0.7,0.0011,-0.015,0.71,0.0029,0.0038,-0.011,0.0037,0.0022,-3.7e+02,-1.3e-05,-5.6e-05,-7.9e-07,0,0,-6.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.04,0.00047,0.00045,0.056,0.32,0.32,7,0.17,0.17,0.33,1.9e-08,1.9e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6190000,0.7,0.0011,-0.015,0.71,-0.00035,0.0027,-0.005,0.0022,0.0015,-3.7e+02,-1.3e-05,-5.6e-05,-7.9e-07,0,0,-8.8e-07,0.21,0.0021,0.43,0,0,0,0,0,0.041,0.00039,0.00036,0.058,0.25,0.25,4.9,0.13,0.13,0.32,1.5e-08,1.5e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6290000,0.7,0.0011,-0.015,0.71,-6.8e-05,0.0039,-0.012,0.0022,0.0019,-3.7e+02,-1.3e-05,-5.6e-05,-7.9e-07,0,0,-9.6e-07,0.21,0.0021,0.43,0,0,0,0,0,0.043,0.00041,0.00038,0.059,0.29,0.29,3.2,0.16,0.16,0.3,1.5e-08,1.5e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6390000,0.7,0.0012,-0.014,0.71,-0.0018,0.0033,-0.05,0.0012,0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-8e-07,0,0,-3.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.044,0.00034,0.00031,0.061,0.23,0.23,2.3,0.12,0.12,0.29,1.3e-08,1.2e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6490000,0.7,0.0012,-0.015,0.71,-0.0017,0.0039,-0.052,0.001,0.0018,-3.7e+02,-1.4e-05,-5.6e-05,-8e-07,0,0,-8.5e-07,0.21,0.0021,0.43,0,0,0,0,0,0.046,0.00036,0.00033,0.063,0.26,0.26,1.5,0.15,0.15,0.26,1.3e-08,1.2e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6590000,0.71,0.0012,-0.015,0.71,-0.0024,0.0029,-0.099,0.00044,0.0014,-3.7e+02,-1.4e-05,-5.7e-05,4e-07,0,0,9.7e-07,0.37,0.0037,0.025,0,0,0,0,0,0.0049,0.00026,0.00026,0.0018,0.19,0.19,1.1,0.12,0.12,0.23,1e-08,1e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6690000,0.7,0.0012,-0.015,0.71,-0.0016,0.0037,-0.076,0.00024,0.0017,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,0,0,-2.2e-06,0.37,0.0037,0.025,0,0,0,0,0,0.0042,0.00026,0.00026,0.0008,0.19,0.19,0.78,0.14,0.14,0.21,1e-08,1e-08,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6790000,0.71,0.0012,-0.014,0.71,-0.0026,0.0034,-0.11,3.7e-05,0.0021,-3.7e+02,-1.4e-05,-5.7e-05,-1.2e-06,0,0,1e-07,0.37,0.0037,0.025,0,0,0,0,0,0.0041,0.00026,0.00026,0.00055,0.2,0.2,0.6,0.17,0.17,0.2,1e-08,1e-08,9.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6890000,0.71,0.0012,-0.014,0.71,-0.0042,0.0037,-0.12,-0.00032,0.0025,-3.7e+02,-1.4e-05,-5.7e-05,2.3e-06,0,0,-4.1e-07,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00026,0.00026,0.00042,0.21,0.21,0.46,0.21,0.21,0.18,1e-08,1e-08,9.6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -6990000,0.7,0.0013,-0.014,0.71,-0.0039,0.0042,-0.12,-0.00073,0.0028,-3.7e+02,-1.4e-05,-5.6e-05,-1.7e-05,0,0,-3.4e-06,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00026,0.00026,0.00036,0.22,0.22,0.36,0.25,0.25,0.16,1e-08,1e-08,9.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7090000,0.7,0.0013,-0.014,0.71,-0.004,0.0034,-0.13,-0.0011,0.003,-3.7e+02,-1.5e-05,-5.6e-05,-3.9e-05,0,0,-7e-06,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00034,0.23,0.23,0.29,0.29,0.29,0.16,1e-08,1e-08,8.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7190000,0.7,0.0013,-0.014,0.71,-0.0053,0.0033,-0.15,-0.0016,0.0033,-3.7e+02,-1.5e-05,-5.6e-05,-4.3e-05,0,0,-4.9e-06,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00033,0.25,0.25,0.24,0.34,0.34,0.15,1e-08,1e-08,8.2e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7290000,0.7,0.0013,-0.014,0.71,-0.0064,0.0034,-0.15,-0.0022,0.0037,-3.7e+02,-1.4e-05,-5.6e-05,-3.5e-05,0,0,-1.2e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00032,0.27,0.27,0.2,0.4,0.4,0.14,1e-08,1e-08,7.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -7390000,0.7,0.0013,-0.014,0.71,-0.006,0.0047,-0.16,-0.0028,0.0042,-3.7e+02,-1.4e-05,-5.6e-05,-2.7e-05,0,0,-1.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00028,0.00028,0.00033,0.29,0.29,0.18,0.46,0.46,0.13,1e-08,1e-08,6.8e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7490000,0.7,0.0014,-0.014,0.71,-0.0072,0.0049,-0.16,-0.0035,0.0047,-3.7e+02,-1.4e-05,-5.6e-05,-2.2e-05,0,0,-2.1e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00028,0.00028,0.00032,0.32,0.32,0.15,0.53,0.53,0.12,1e-08,9.9e-09,6e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7590000,0.7,0.0014,-0.014,0.71,-0.0086,0.0061,-0.17,-0.0042,0.0054,-3.7e+02,-1.4e-05,-5.7e-05,-5.2e-06,0,0,-3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00029,0.00028,0.00032,0.35,0.35,0.14,0.6,0.6,0.12,1e-08,9.9e-09,5.3e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7690000,0.7,0.0014,-0.014,0.71,-0.0099,0.0067,-0.16,-0.0051,0.006,-3.7e+02,-1.4e-05,-5.7e-05,-5e-06,0,0,-5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00029,0.00029,0.00032,0.38,0.38,0.13,0.69,0.69,0.11,9.9e-09,9.9e-09,4.7e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7790000,0.7,0.0015,-0.014,0.71,-0.011,0.0072,-0.16,-0.0061,0.0064,-3.7e+02,-1.4e-05,-5.6e-05,-2.5e-05,0,0,-7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.0003,0.0003,0.00031,0.41,0.41,0.12,0.78,0.78,0.11,9.8e-09,9.8e-09,4e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -7890000,0.7,0.0015,-0.014,0.71,-0.013,0.0089,-0.16,-0.0073,0.0073,-3.7e+02,-1.4e-05,-5.6e-05,-1.3e-05,0,0,-9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.0003,0.0003,0.00031,0.45,0.45,0.11,0.89,0.89,0.1,9.8e-09,9.8e-09,3.5e-07,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -7990000,0.7,0.0015,-0.014,0.71,-0.014,0.0099,-0.16,-0.0086,0.0083,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,0,0,-0.00011,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00031,0.00031,0.0003,0.49,0.49,0.1,1,1,0.099,9.7e-09,9.7e-09,3e-07,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -8090000,0.7,0.0015,-0.014,0.71,-0.016,0.011,-0.17,-0.01,0.0095,-3.7e+02,-1.4e-05,-5.7e-05,8.2e-06,0,0,-0.00011,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00032,0.00031,0.00029,0.53,0.53,0.1,1.1,1.1,0.097,9.7e-09,9.7e-09,2.6e-07,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 -8190000,0.7,0.0015,-0.014,0.71,-0.018,0.012,-0.18,-0.012,0.01,-3.7e+02,-1.4e-05,-5.7e-05,-2.9e-06,0,0,-0.00013,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00032,0.00032,0.00028,0.58,0.58,0.099,1.3,1.3,0.094,9.7e-09,9.7e-09,2.3e-07,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 -8290000,0.7,0.0015,-0.014,0.71,-0.019,0.013,-0.17,-0.014,0.011,-3.7e+02,-1.4e-05,-5.6e-05,-8.4e-06,0,0,-0.00017,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00033,0.00033,0.00027,0.63,0.63,0.097,1.4,1.4,0.091,9.6e-09,9.6e-09,2e-07,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0 -8390000,0.7,0.0016,-0.014,0.71,-0.02,0.014,-0.17,-0.016,0.013,-3.7e+02,-1.4e-05,-5.7e-05,1.5e-06,0,0,-0.00021,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00034,0.00034,0.00027,0.68,0.68,0.097,1.6,1.6,0.091,9.6e-09,9.6e-09,1.8e-07,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0 -8490000,0.7,0.0015,-0.014,0.71,-0.021,0.015,-0.17,-0.017,0.014,-3.7e+02,-1.4e-05,-5.7e-05,-2.2e-06,0,0,-0.00025,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00034,0.00034,0.00026,0.73,0.73,0.096,1.8,1.8,0.089,9.5e-09,9.5e-09,1.5e-07,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0 -8590000,0.7,0.0016,-0.014,0.71,-0.023,0.017,-0.17,-0.02,0.015,-3.7e+02,-1.4e-05,-5.6e-05,-9.2e-06,0,0,-0.00029,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00035,0.00035,0.00025,0.79,0.79,0.095,2,2,0.088,9.5e-09,9.5e-09,1.3e-07,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0 -8690000,0.7,0.0016,-0.014,0.71,-0.026,0.018,-0.16,-0.022,0.017,-3.7e+02,-1.4e-05,-5.7e-05,9e-07,0,0,-0.00035,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00036,0.00036,0.00024,0.84,0.84,0.096,2.2,2.2,0.088,9.4e-09,9.4e-09,1.2e-07,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0 -8790000,0.7,0.0016,-0.014,0.71,-0.027,0.019,-0.15,-0.025,0.018,-3.7e+02,-1.4e-05,-5.7e-05,-3.1e-06,0,0,-0.00041,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00037,0.00037,0.00023,0.91,0.91,0.095,2.5,2.5,0.087,9.4e-09,9.4e-09,1.1e-07,4e-06,4e-06,3.2e-06,0,0,0,0,0,0,0,0 -8890000,0.7,0.0016,-0.014,0.71,-0.029,0.02,-0.15,-0.027,0.02,-3.7e+02,-1.4e-05,-5.7e-05,-5.1e-06,0,0,-0.00045,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00037,0.00037,0.00022,0.96,0.96,0.095,2.7,2.7,0.086,9.2e-09,9.2e-09,9.4e-08,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0 -8990000,0.7,0.0016,-0.014,0.71,-0.03,0.02,-0.14,-0.03,0.021,-3.7e+02,-1.4e-05,-5.6e-05,-1e-05,0,0,-0.00051,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00038,0.00038,0.00022,1,1,0.096,3,3,0.087,9.2e-09,9.2e-09,8.5e-08,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0 -9090000,0.7,0.0017,-0.014,0.71,-0.032,0.02,-0.14,-0.033,0.022,-3.7e+02,-1.4e-05,-5.6e-05,-1.2e-05,0,0,-0.00053,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00038,0.00038,0.00021,1.1,1.1,0.095,3.3,3.3,0.086,9.1e-09,9.1e-09,7.6e-08,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0 -9190000,0.7,0.0017,-0.014,0.71,-0.033,0.021,-0.14,-0.036,0.025,-3.7e+02,-1.4e-05,-5.7e-05,-9.6e-07,0,0,-0.00057,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00039,0.00039,0.0002,1.2,1.2,0.094,3.6,3.6,0.085,9.1e-09,9.1e-09,6.8e-08,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0 -9290000,0.7,0.0016,-0.014,0.71,-0.033,0.022,-0.14,-0.038,0.026,-3.7e+02,-1.4e-05,-5.7e-05,1.3e-07,0,0,-0.00061,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00039,0.00039,0.0002,1.2,1.2,0.093,3.9,3.9,0.085,8.9e-09,8.9e-09,6.1e-08,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0 -9390000,0.7,0.0016,-0.014,0.71,-0.034,0.024,-0.14,-0.042,0.028,-3.7e+02,-1.4e-05,-5.7e-05,2e-09,0,0,-0.00065,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.0004,0.00019,1.3,1.3,0.093,4.3,4.3,0.086,8.9e-09,8.9e-09,5.6e-08,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0 -9490000,0.7,0.0016,-0.014,0.71,-0.034,0.023,-0.13,-0.044,0.029,-3.7e+02,-1.3e-05,-5.7e-05,5.9e-06,0,0,-0.00068,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.0004,0.0004,0.00019,1.3,1.3,0.091,4.6,4.6,0.085,8.7e-09,8.7e-09,5e-08,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0 -9590000,0.7,0.0016,-0.014,0.71,-0.036,0.024,-0.13,-0.047,0.031,-3.7e+02,-1.3e-05,-5.7e-05,6.9e-06,0,0,-0.00072,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00018,1.4,1.4,0.09,5.1,5.1,0.085,8.7e-09,8.7e-09,4.6e-08,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0 -9690000,0.7,0.0017,-0.014,0.71,-0.037,0.025,-0.12,-0.049,0.031,-3.7e+02,-1.3e-05,-5.7e-05,1.3e-06,0,0,-0.00077,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00018,1.4,1.4,0.089,5.3,5.3,0.086,8.5e-09,8.5e-09,4.2e-08,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0 -9790000,0.7,0.0016,-0.014,0.71,-0.036,0.027,-0.11,-0.053,0.034,-3.7e+02,-1.3e-05,-5.7e-05,4.4e-06,0,0,-0.00082,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00017,1.5,1.5,0.087,5.9,5.9,0.085,8.5e-09,8.5e-09,3.8e-08,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0 -9890000,0.7,0.0016,-0.014,0.71,-0.036,0.027,-0.11,-0.053,0.034,-3.7e+02,-1.3e-05,-5.7e-05,3.7e-06,0,0,-0.00085,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00017,1.5,1.5,0.084,6.1,6.1,0.085,8.2e-09,8.2e-09,3.5e-08,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0 -9990000,0.7,0.0017,-0.014,0.71,-0.038,0.027,-0.1,-0.057,0.037,-3.7e+02,-1.3e-05,-5.7e-05,1.5e-06,0,0,-0.00089,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00016,1.6,1.6,0.083,6.7,6.7,0.086,8.2e-09,8.2e-09,3.3e-08,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0 -10090000,0.7,0.0017,-0.014,0.71,-0.036,0.026,-0.096,-0.057,0.036,-3.7e+02,-1.3e-05,-5.7e-05,2.3e-06,0,0,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00016,1.6,1.6,0.08,6.9,6.9,0.085,8e-09,8e-09,3e-08,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0 -10190000,0.7,0.0017,-0.014,0.71,-0.037,0.028,-0.096,-0.061,0.039,-3.7e+02,-1.3e-05,-5.7e-05,-2.9e-06,0,0,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00015,1.7,1.7,0.078,7.6,7.6,0.084,8e-09,8e-09,2.7e-08,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 -10290000,0.7,0.0017,-0.014,0.71,-0.038,0.028,-0.084,-0.065,0.041,-3.7e+02,-1.3e-05,-5.7e-05,-5.7e-06,0,0,-0.00098,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00043,0.00043,0.00015,1.8,1.8,0.076,8.3,8.3,0.085,8e-09,8e-09,2.6e-08,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 -10390000,0.7,0.0016,-0.014,0.71,0.01,-0.02,0.0096,0.0009,-0.0018,-3.7e+02,-1.3e-05,-5.7e-05,-5.1e-06,-6.4e-10,5.1e-10,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00045,0.00045,0.00015,0.25,0.25,0.56,0.25,0.25,0.078,8e-09,8e-09,2.4e-08,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0 -10490000,0.7,0.0017,-0.014,0.71,0.0097,-0.018,0.023,0.0019,-0.0036,-3.7e+02,-1.3e-05,-5.7e-05,-7.3e-06,-1.7e-08,1.3e-08,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00046,0.00046,0.00014,0.26,0.26,0.55,0.26,0.26,0.08,8e-09,8e-09,2.2e-08,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 -10590000,0.7,0.0017,-0.014,0.71,0.0092,-0.0076,0.026,0.0018,-0.00084,-3.7e+02,-1.3e-05,-5.7e-05,-6.6e-06,-2.8e-06,7.5e-08,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00047,0.00047,0.00014,0.13,0.13,0.27,0.13,0.13,0.073,7.9e-09,7.9e-09,2e-08,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 -10690000,0.7,0.0018,-0.014,0.71,0.0079,-0.0075,0.03,0.0027,-0.0016,-3.7e+02,-1.3e-05,-5.7e-05,-7e-06,-2.8e-06,8.7e-08,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00048,0.00014,0.14,0.14,0.26,0.14,0.14,0.078,7.9e-09,7.9e-09,1.9e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -10790000,0.7,0.0018,-0.014,0.71,0.0072,-0.0048,0.024,0.0028,-0.0008,-3.7e+02,-1.3e-05,-5.6e-05,-6.2e-06,-5e-06,7.1e-07,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00047,0.00013,0.099,0.099,0.17,0.091,0.091,0.072,7.8e-09,7.8e-09,1.8e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -10890000,0.7,0.0017,-0.014,0.71,0.0067,-0.0041,0.02,0.0034,-0.0012,-3.7e+02,-1.3e-05,-5.6e-05,-5.9e-06,-5e-06,7e-07,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00049,0.00049,0.00013,0.11,0.11,0.16,0.098,0.098,0.075,7.8e-09,7.8e-09,1.6e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -10990000,0.7,0.0017,-0.014,0.71,0.0086,0.00072,0.014,0.0048,-0.0024,-3.7e+02,-1.3e-05,-5.6e-05,-3.4e-06,-1e-05,6.1e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00047,0.00047,0.00013,0.09,0.09,0.12,0.073,0.073,0.071,7.5e-09,7.5e-09,1.5e-08,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0 -11090000,0.7,0.0017,-0.014,0.71,0.0079,0.0025,0.019,0.0056,-0.0023,-3.7e+02,-1.3e-05,-5.6e-05,-1.2e-06,-1e-05,6.1e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00048,0.00012,0.11,0.11,0.11,0.079,0.079,0.074,7.5e-09,7.5e-09,1.4e-08,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0 -11190000,0.7,0.0017,-0.014,0.71,0.012,0.0053,0.0077,0.0067,-0.0031,-3.7e+02,-1.2e-05,-5.6e-05,-2.5e-06,-1.3e-05,1.1e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00044,0.00044,0.00012,0.088,0.088,0.084,0.063,0.063,0.069,7e-09,7e-09,1.4e-08,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 -11290000,0.7,0.0018,-0.014,0.71,0.012,0.0071,0.0074,0.0079,-0.0024,-3.7e+02,-1.2e-05,-5.6e-05,-4.8e-06,-1.3e-05,1.1e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00045,0.00045,0.00012,0.11,0.11,0.078,0.07,0.07,0.072,7e-09,7e-09,1.3e-08,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0 -11390000,0.7,0.0019,-0.014,0.71,0.0072,0.0067,0.0017,0.0057,-0.0022,-3.7e+02,-1.3e-05,-5.6e-05,-6.4e-06,-9.9e-06,5.3e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0004,0.0004,0.00012,0.089,0.089,0.063,0.057,0.057,0.068,6.5e-09,6.5e-09,1.2e-08,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11490000,0.7,0.0019,-0.014,0.71,0.0051,0.009,0.0025,0.0063,-0.0014,-3.7e+02,-1.3e-05,-5.6e-05,-9.5e-06,-9.9e-06,5.3e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00041,0.00041,0.00011,0.11,0.11,0.058,0.065,0.065,0.069,6.5e-09,6.5e-09,1.1e-08,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11590000,0.7,0.0019,-0.014,0.71,0.00041,0.0084,-0.0034,0.0047,-0.0015,-3.7e+02,-1.3e-05,-5.6e-05,-9.8e-06,-5.8e-06,2.7e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00036,0.00036,0.00011,0.089,0.089,0.049,0.054,0.054,0.066,6e-09,6e-09,1.1e-08,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11690000,0.7,0.0018,-0.014,0.71,-0.0021,0.011,-0.0079,0.0046,-0.00059,-3.7e+02,-1.3e-05,-5.6e-05,-1e-05,-5.7e-06,2.6e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00037,0.00037,0.00011,0.11,0.11,0.046,0.062,0.062,0.066,6e-09,6e-09,1e-08,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0 -11790000,0.7,0.0019,-0.014,0.71,-0.0081,0.011,-0.0098,0.0021,0.00045,-3.7e+02,-1.4e-05,-5.6e-05,-1e-05,-5.1e-06,-1e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00032,0.00032,0.00011,0.087,0.087,0.039,0.052,0.052,0.063,5.5e-09,5.6e-09,9.5e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0 -11890000,0.7,0.0019,-0.014,0.71,-0.0093,0.012,-0.011,0.0012,0.0016,-3.7e+02,-1.4e-05,-5.6e-05,-1.1e-05,-5.2e-06,-9.6e-07,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00033,0.00033,0.00011,0.1,0.1,0.037,0.06,0.06,0.063,5.5e-09,5.6e-09,9e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0 -11990000,0.7,0.002,-0.014,0.71,-0.011,0.013,-0.016,-6.6e-05,0.0022,-3.7e+02,-1.4e-05,-5.6e-05,-1.1e-05,-3.9e-06,-1.4e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00029,0.00029,0.00011,0.083,0.083,0.033,0.051,0.051,0.061,5.1e-09,5.1e-09,8.5e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0 -12090000,0.7,0.002,-0.014,0.71,-0.013,0.015,-0.022,-0.0013,0.0036,-3.7e+02,-1.4e-05,-5.7e-05,-9e-06,-3.7e-06,-1.6e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00029,0.00029,0.0001,0.099,0.099,0.031,0.059,0.059,0.061,5.1e-09,5.1e-09,8.1e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0 -12190000,0.7,0.0017,-0.014,0.71,-0.007,0.012,-0.017,0.0015,0.002,-3.7e+02,-1.3e-05,-5.7e-05,-8.2e-06,2.1e-07,5.6e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00026,0.00026,0.0001,0.079,0.079,0.028,0.05,0.05,0.059,4.8e-09,4.8e-09,7.6e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0 -12290000,0.7,0.0017,-0.014,0.71,-0.0094,0.014,-0.016,0.00068,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-7.7e-06,-5.6e-08,5.9e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00027,0.00027,0.0001,0.093,0.093,0.028,0.058,0.058,0.059,4.8e-09,4.8e-09,7.3e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0 -12390000,0.7,0.0014,-0.014,0.71,-0.0045,0.011,-0.015,0.0029,0.0018,-3.7e+02,-1.2e-05,-5.7e-05,-8.3e-06,2.9e-06,1.1e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00024,0.00024,9.8e-05,0.075,0.075,0.026,0.05,0.05,0.057,4.5e-09,4.5e-09,6.9e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0 -12490000,0.7,0.0014,-0.014,0.71,-0.0056,0.013,-0.018,0.0024,0.003,-3.7e+02,-1.2e-05,-5.7e-05,-9.2e-06,2.8e-06,1.1e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00025,0.00025,9.6e-05,0.087,0.087,0.026,0.058,0.058,0.057,4.5e-09,4.5e-09,6.6e-09,3.5e-06,3.5e-06,1e-06,0,0,0,0,0,0,0,0 -12590000,0.7,0.0015,-0.014,0.71,-0.013,0.011,-0.023,-0.0027,0.0016,-3.7e+02,-1.3e-05,-5.8e-05,-8.9e-06,5.5e-06,6.1e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00022,0.00022,9.5e-05,0.07,0.07,0.025,0.049,0.049,0.055,4.3e-09,4.3e-09,6.3e-09,3.5e-06,3.5e-06,9.9e-07,0,0,0,0,0,0,0,0 -12690000,0.7,0.0015,-0.014,0.71,-0.013,0.012,-0.027,-0.0041,0.0028,-3.7e+02,-1.3e-05,-5.8e-05,-9.4e-06,5.8e-06,5.9e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00023,0.00023,9.3e-05,0.081,0.081,0.025,0.058,0.058,0.055,4.3e-09,4.3e-09,6e-09,3.5e-06,3.5e-06,9.8e-07,0,0,0,0,0,0,0,0 -12790000,0.7,0.0015,-0.014,0.71,-0.019,0.0092,-0.03,-0.0075,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-8.7e-06,7.4e-06,4.2e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00021,0.00021,9.2e-05,0.066,0.066,0.024,0.049,0.049,0.053,4e-09,4e-09,5.7e-09,3.5e-06,3.5e-06,9.7e-07,0,0,0,0,0,0,0,0 -12890000,0.7,0.0015,-0.014,0.71,-0.02,0.0092,-0.029,-0.0094,0.0024,-3.7e+02,-1.3e-05,-5.8e-05,-8.2e-06,6.8e-06,4.7e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00022,0.00022,9.1e-05,0.076,0.076,0.025,0.057,0.057,0.054,4e-09,4e-09,5.4e-09,3.5e-06,3.5e-06,9.6e-07,0,0,0,0,0,0,0,0 -12990000,0.7,0.0012,-0.014,0.71,-0.0078,0.0067,-0.03,-0.0011,0.0013,-3.7e+02,-1.2e-05,-5.8e-05,-6.8e-06,6.9e-06,9.8e-06,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.9e-05,0.062,0.062,0.025,0.049,0.049,0.052,3.8e-09,3.9e-09,5.2e-09,3.5e-06,3.5e-06,9.4e-07,0,0,0,0,0,0,0,0 -13090000,0.7,0.0012,-0.014,0.71,-0.0084,0.0069,-0.03,-0.0019,0.002,-3.7e+02,-1.2e-05,-5.8e-05,-7.8e-06,6.6e-06,1e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00021,0.00021,8.8e-05,0.071,0.071,0.025,0.057,0.057,0.052,3.8e-09,3.9e-09,4.9e-09,3.5e-06,3.5e-06,9.4e-07,0,0,0,0,0,0,0,0 -13190000,0.7,0.00097,-0.014,0.71,0.00038,0.0064,-0.027,0.0043,0.0013,-3.7e+02,-1.2e-05,-5.9e-05,-7.5e-06,5.3e-06,1.3e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.6e-05,0.058,0.058,0.025,0.049,0.049,0.051,3.7e-09,3.7e-09,4.7e-09,3.5e-06,3.5e-06,9.1e-07,0,0,0,0,0,0,0,0 -13290000,0.7,0.00097,-0.014,0.71,0.0002,0.0073,-0.024,0.0043,0.002,-3.7e+02,-1.2e-05,-5.9e-05,-6.3e-06,4e-06,1.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.5e-05,0.067,0.067,0.027,0.057,0.057,0.051,3.7e-09,3.7e-09,4.5e-09,3.5e-06,3.5e-06,9.1e-07,0,0,0,0,0,0,0,0 -13390000,0.7,0.00082,-0.014,0.71,0.00098,0.0062,-0.02,0.0032,0.0012,-3.7e+02,-1.1e-05,-5.9e-05,-5.3e-06,2.7e-06,1.5e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,8.4e-05,0.055,0.055,0.026,0.048,0.048,0.05,3.5e-09,3.5e-09,4.3e-09,3.5e-06,3.5e-06,8.8e-07,0,0,0,0,0,0,0,0 -13490000,0.7,0.00085,-0.014,0.71,0.00055,0.0062,-0.019,0.0033,0.0018,-3.7e+02,-1.1e-05,-5.9e-05,-4.5e-06,1.9e-06,1.5e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.2e-05,0.063,0.063,0.028,0.056,0.056,0.05,3.5e-09,3.5e-09,4.1e-09,3.5e-06,3.5e-06,8.7e-07,0,0,0,0,0,0,0,0 -13590000,0.7,0.0008,-0.014,0.71,0.00075,0.0064,-0.021,0.0023,0.0012,-3.7e+02,-1.1e-05,-5.9e-05,-4.9e-06,1.8e-06,1.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,8.2e-05,0.052,0.052,0.028,0.048,0.048,0.05,3.4e-09,3.4e-09,4e-09,3.5e-06,3.5e-06,8.4e-07,0,0,0,0,0,0,0,0 -13690000,0.7,0.00077,-0.014,0.71,0.0015,0.0083,-0.025,0.0024,0.0019,-3.7e+02,-1.1e-05,-5.9e-05,-3.8e-06,2.1e-06,1.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8e-05,0.059,0.059,0.029,0.056,0.056,0.05,3.4e-09,3.4e-09,3.8e-09,3.5e-06,3.5e-06,8.3e-07,0,0,0,0,0,0,0,0 -13790000,0.7,0.00066,-0.014,0.71,0.002,0.0041,-0.027,0.0034,-0.00048,-3.7e+02,-1.1e-05,-5.9e-05,-3.7e-06,6.1e-07,1.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.9e-05,0.05,0.05,0.029,0.048,0.048,0.049,3.2e-09,3.2e-09,3.7e-09,3.5e-06,3.5e-06,7.9e-07,0,0,0,0,0,0,0,0 -13890000,0.7,0.00063,-0.014,0.71,0.0026,0.0041,-0.031,0.0036,-9.1e-05,-3.7e+02,-1.1e-05,-5.9e-05,-3e-06,9.1e-07,1.3e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.9e-05,0.056,0.056,0.03,0.056,0.056,0.05,3.2e-09,3.2e-09,3.5e-09,3.5e-06,3.5e-06,7.8e-07,0,0,0,0,0,0,0,0 -13990000,0.7,0.00056,-0.014,0.71,0.0028,0.0016,-0.03,0.0044,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-2.8e-06,-1.3e-06,1.3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.7e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-09,3.1e-09,3.4e-09,3.5e-06,3.5e-06,7.4e-07,0,0,0,0,0,0,0,0 -14090000,0.7,0.00054,-0.014,0.71,0.0029,0.0018,-0.031,0.0047,-0.0017,-3.7e+02,-1.1e-05,-6e-05,-1.7e-06,-1.2e-06,1.3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.6e-05,0.054,0.054,0.031,0.055,0.055,0.05,3.1e-09,3.1e-09,3.2e-09,3.5e-06,3.5e-06,7.3e-07,0,0,0,0,0,0,0,0 -14190000,0.7,0.00044,-0.014,0.71,0.0062,0.0012,-0.033,0.0067,-0.0015,-3.7e+02,-1.1e-05,-6e-05,-1.1e-06,-1.5e-06,1.1e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.6e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,3.1e-09,3.5e-06,3.5e-06,6.9e-07,0,0,0,0,0,0,0,0 -14290000,0.7,0.00045,-0.014,0.71,0.0071,0.002,-0.032,0.0074,-0.0014,-3.7e+02,-1.1e-05,-6e-05,-6.5e-07,-2.2e-06,1.1e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.5e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,3e-09,3.5e-06,3.5e-06,6.7e-07,0,0,0,0,0,0,0,0 -14390000,0.7,0.00036,-0.014,0.71,0.0088,0.0029,-0.034,0.0087,-0.0012,-3.7e+02,-1e-05,-6e-05,4.1e-07,-2.6e-06,9.2e-06,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7.3e-05,0.044,0.044,0.031,0.047,0.047,0.05,2.8e-09,2.8e-09,2.9e-09,3.4e-06,3.4e-06,6.3e-07,0,0,0,0,0,0,0,0 -14490000,0.7,0.00035,-0.014,0.71,0.0089,0.0042,-0.037,0.0096,-0.00085,-3.7e+02,-1e-05,-6e-05,7e-07,-2.1e-06,8.8e-06,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.2e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-09,2.8e-09,2.8e-09,3.4e-06,3.4e-06,6.2e-07,0,0,0,0,0,0,0,0 -14590000,0.7,0.00034,-0.013,0.71,0.0054,0.0026,-0.037,0.006,-0.0023,-3.7e+02,-1.1e-05,-6e-05,7.2e-07,-5e-06,1.3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7.2e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,2.7e-09,3.4e-06,3.4e-06,5.8e-07,0,0,0,0,0,0,0,0 -14690000,0.7,0.0003,-0.013,0.71,0.0069,-0.00029,-0.034,0.0067,-0.0022,-3.7e+02,-1.1e-05,-6e-05,1.4e-06,-6e-06,1.4e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.1e-05,0.048,0.048,0.032,0.054,0.054,0.051,2.6e-09,2.6e-09,2.6e-09,3.4e-06,3.4e-06,5.6e-07,0,0,0,0,0,0,0,0 -14790000,0.7,0.00032,-0.013,0.71,0.0036,-0.0019,-0.03,0.0038,-0.0032,-3.7e+02,-1.1e-05,-6e-05,1.6e-06,-9.3e-06,1.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-09,2.5e-09,2.5e-09,3.4e-06,3.4e-06,5.3e-07,0,0,0,0,0,0,0,0 -14890000,0.7,0.00031,-0.013,0.71,0.0052,-0.00087,-0.033,0.0042,-0.0034,-3.7e+02,-1.1e-05,-6e-05,2e-06,-9.1e-06,1.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,6.9e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-09,2.5e-09,2.4e-09,3.4e-06,3.4e-06,5.1e-07,0,0,0,0,0,0,0,0 -14990000,0.7,0.00031,-0.013,0.71,0.004,-0.0011,-0.029,0.0032,-0.0027,-3.7e+02,-1.1e-05,-6e-05,1.8e-06,-9.8e-06,2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.8e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-09,2.3e-09,2.3e-09,3.4e-06,3.4e-06,4.8e-07,0,0,0,0,0,0,0,0 -15090000,0.7,0.00023,-0.013,0.71,0.0045,-0.0012,-0.032,0.0036,-0.0028,-3.7e+02,-1.1e-05,-6e-05,1.8e-06,-9.3e-06,2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,6.8e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-09,2.3e-09,2.3e-09,3.4e-06,3.4e-06,4.6e-07,0,0,0,0,0,0,0,0 -15190000,0.7,0.00025,-0.013,0.71,0.0038,-6.2e-05,-0.029,0.0029,-0.0023,-3.7e+02,-1.1e-05,-6e-05,1.7e-06,-9.6e-06,2.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.7e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-09,2.2e-09,2.2e-09,3.4e-06,3.4e-06,4.3e-07,0,0,0,0,0,0,0,0 -15290000,0.7,0.00021,-0.013,0.71,0.0044,0.00018,-0.027,0.0033,-0.0023,-3.7e+02,-1.1e-05,-6e-05,2.1e-06,-1e-05,2.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.6e-05,0.045,0.045,0.03,0.053,0.053,0.052,2.2e-09,2.2e-09,2.1e-09,3.4e-06,3.4e-06,4.2e-07,0,0,0,0,0,0,0,0 -15390000,0.71,0.00021,-0.013,0.71,0.0037,0.00045,-0.024,0.00067,-0.0019,-3.7e+02,-1.2e-05,-6e-05,3e-06,-1.1e-05,2.5e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.5e-05,0.039,0.039,0.029,0.047,0.047,0.051,2e-09,2e-09,2e-09,3.4e-06,3.4e-06,3.9e-07,0,0,0,0,0,0,0,0 -15490000,0.7,0.00023,-0.013,0.71,0.005,0.00015,-0.024,0.0011,-0.0019,-3.7e+02,-1.2e-05,-6e-05,2.5e-06,-1.1e-05,2.4e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.5e-05,0.044,0.044,0.029,0.053,0.053,0.053,2e-09,2e-09,2e-09,3.4e-06,3.4e-06,3.7e-07,0,0,0,0,0,0,0,0 -15590000,0.7,0.00024,-0.013,0.71,0.003,7.8e-05,-0.023,-0.0012,-0.0016,-3.7e+02,-1.2e-05,-6e-05,2.1e-06,-1.1e-05,2.6e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.9e-09,3.3e-06,3.3e-06,3.5e-07,0,0,0,0,0,0,0,0 -15690000,0.7,0.00025,-0.013,0.71,0.0034,-1.7e-05,-0.023,-0.00087,-0.0015,-3.7e+02,-1.2e-05,-6e-05,2.1e-06,-1.1e-05,2.6e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.3e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.8e-09,3.3e-06,3.3e-06,3.3e-07,0,0,0,0,0,0,0,0 -15790000,0.7,0.00021,-0.013,0.71,0.0038,-0.0017,-0.026,-0.00083,-0.0026,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.3e-05,2.7e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.3e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-09,1.7e-09,1.8e-09,3.3e-06,3.3e-06,3.1e-07,0,0,0,0,0,0,0,0 -15890000,0.7,0.00016,-0.013,0.71,0.0048,-0.0022,-0.024,-0.00037,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,2.2e-06,-1.3e-05,2.7e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.2e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-09,1.7e-09,1.7e-09,3.3e-06,3.3e-06,3e-07,0,0,0,0,0,0,0,0 -15990000,0.71,0.0001,-0.013,0.71,0.0046,-0.0031,-0.019,-0.0005,-0.0037,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.6e-05,3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.1e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-09,1.6e-09,1.7e-09,3.3e-06,3.3e-06,2.8e-07,0,0,0,0,0,0,0,0 -16090000,0.71,0.0001,-0.013,0.71,0.0064,-0.0033,-0.016,4.1e-05,-0.004,-3.7e+02,-1.2e-05,-6.1e-05,3.6e-06,-1.7e-05,3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.1e-05,0.042,0.042,0.025,0.053,0.053,0.052,1.6e-09,1.6e-09,1.6e-09,3.3e-06,3.3e-06,2.7e-07,0,0,0,0,0,0,0,0 -16190000,0.71,0.00013,-0.013,0.71,0.0063,-0.0026,-0.014,-0.00022,-0.0033,-3.7e+02,-1.2e-05,-6.1e-05,3.7e-06,-1.6e-05,3.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00016,6e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.6e-09,3.3e-06,3.3e-06,2.5e-07,0,0,0,0,0,0,0,0 -16290000,0.71,0.00014,-0.013,0.71,0.008,-0.0033,-0.016,0.0005,-0.0036,-3.7e+02,-1.2e-05,-6.1e-05,4.4e-06,-1.6e-05,3.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6e-05,0.042,0.042,0.024,0.052,0.052,0.052,1.5e-09,1.5e-09,1.5e-09,3.3e-06,3.3e-06,2.4e-07,0,0,0,0,0,0,0,0 -16390000,0.71,0.00013,-0.013,0.71,0.0068,-0.0036,-0.015,0.00012,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,4.2e-06,-1.5e-05,3.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.9e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1.5e-09,3.2e-06,3.2e-06,2.2e-07,0,0,0,0,0,0,0,0 -16490000,0.71,0.00015,-0.013,0.71,0.0061,-0.0031,-0.018,0.00074,-0.0032,-3.7e+02,-1.2e-05,-6.1e-05,4.3e-06,-1.4e-05,3.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00016,5.9e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1.4e-09,3.2e-06,3.2e-06,2.1e-07,0,0,0,0,0,0,0,0 -16590000,0.71,0.0004,-0.013,0.71,0.0025,-0.00048,-0.018,-0.0023,0.00012,-3.7e+02,-1.3e-05,-6e-05,4.4e-06,-7.4e-06,4.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.8e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-09,1.2e-09,1.4e-09,3.2e-06,3.2e-06,2e-07,0,0,0,0,0,0,0,0 -16690000,0.71,0.00039,-0.013,0.71,0.0027,4.3e-05,-0.015,-0.002,0.0001,-3.7e+02,-1.3e-05,-6e-05,4e-06,-8e-06,4.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-09,1.2e-09,1.4e-09,3.2e-06,3.2e-06,1.9e-07,0,0,0,0,0,0,0,0 -16790000,0.71,0.00054,-0.013,0.71,-0.00072,0.0022,-0.014,-0.0044,0.0027,-3.7e+02,-1.3e-05,-6e-05,4.1e-06,-2.1e-06,4.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-09,1.1e-09,1.3e-09,3.2e-06,3.2e-06,1.8e-07,0,0,0,0,0,0,0,0 -16890000,0.71,0.00056,-0.013,0.71,-0.00095,0.0031,-0.011,-0.0045,0.003,-3.7e+02,-1.3e-05,-6e-05,3.9e-06,-2.5e-06,5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.6e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-09,1.1e-09,1.3e-09,3.2e-06,3.2e-06,1.7e-07,0,0,0,0,0,0,0,0 -16990000,0.71,0.0005,-0.013,0.71,-0.00098,0.001,-0.01,-0.005,0.0011,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-6.5e-06,5.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.6e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-09,1e-09,1.2e-09,3.2e-06,3.2e-06,1.6e-07,0,0,0,0,0,0,0,0 -17090000,0.71,0.00046,-0.013,0.71,-0.00014,0.002,-0.01,-0.0051,0.0012,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-6.4e-06,5.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.5e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-09,1e-09,1.2e-09,3.2e-06,3.2e-06,1.6e-07,0,0,0,0,0,0,0,0 -17190000,0.71,0.00045,-0.013,0.71,0.00024,0.0019,-0.011,-0.0054,-0.00032,-3.7e+02,-1.3e-05,-6e-05,3.8e-06,-9.9e-06,5.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.5e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-10,9.4e-10,1.2e-09,3.1e-06,3.1e-06,1.5e-07,0,0,0,0,0,0,0,0 -17290000,0.71,0.00043,-0.013,0.71,0.0024,0.003,-0.0066,-0.0053,-9.1e-05,-3.7e+02,-1.3e-05,-6e-05,3.4e-06,-1e-05,5.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.4e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-10,9.4e-10,1.2e-09,3.1e-06,3.1e-06,1.4e-07,0,0,0,0,0,0,0,0 -17390000,0.71,0.00039,-0.013,0.71,0.003,0.0021,-0.0047,-0.0045,-0.0014,-3.7e+02,-1.3e-05,-6e-05,3.8e-06,-1.4e-05,5.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.4e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-10,8.5e-10,1.1e-09,3.1e-06,3.1e-06,1.3e-07,0,0,0,0,0,0,0,0 -17490000,0.71,0.00039,-0.013,0.71,0.0035,0.0017,-0.003,-0.0042,-0.0012,-3.7e+02,-1.3e-05,-6e-05,3.8e-06,-1.4e-05,5.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-10,8.5e-10,1.1e-09,3.1e-06,3.1e-06,1.3e-07,0,0,0,0,0,0,0,0 -17590000,0.71,0.0003,-0.013,0.71,0.0047,0.0005,0.0025,-0.0035,-0.0024,-3.7e+02,-1.3e-05,-6.1e-05,3.9e-06,-1.8e-05,5.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-10,7.7e-10,1.1e-09,3.1e-06,3.1e-06,1.2e-07,0,0,0,0,0,0,0,0 -17690000,0.71,0.00027,-0.013,0.71,0.0057,0.0013,0.0019,-0.003,-0.0023,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.2e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-10,7.7e-10,1e-09,3.1e-06,3.1e-06,1.2e-07,0,0,0,0,0,0,0,0 -17790000,0.71,0.00018,-0.013,0.71,0.0082,0.0009,0.00059,-0.0019,-0.002,-3.7e+02,-1.3e-05,-6.1e-05,4.8e-06,-1.7e-05,5.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.2e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-10,7e-10,1e-09,3.1e-06,3.1e-06,1.1e-07,0,0,0,0,0,0,0,0 -17890000,0.71,0.00019,-0.013,0.71,0.0097,0.00018,0.00069,-0.00099,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,5.1e-06,-1.7e-05,5.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.2e-05,0.037,0.037,0.016,0.051,0.051,0.048,7e-10,7e-10,9.8e-10,3.1e-06,3.1e-06,1.1e-07,0,0,0,0,0,0,0,0 -17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0016,0.0019,-0.00034,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,5e-06,-1.7e-05,5.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.1e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,9.6e-10,3e-06,3e-06,1e-07,0,0,0,0,0,0,0,0 -18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0018,0.0043,0.00083,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.7e-05,5.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.1e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,9.3e-10,3e-06,3e-06,9.7e-08,0,0,0,0,0,0,0,0 -18190000,0.71,0.0001,-0.013,0.71,0.013,-0.00074,0.0056,0.0016,-0.0015,-3.7e+02,-1.3e-05,-6e-05,4.8e-06,-1.7e-05,5.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,9.1e-10,3e-06,3e-06,9.2e-08,0,0,0,0,0,0,0,0 -18290000,0.71,4.6e-05,-0.013,0.71,0.013,-0.0013,0.0068,0.0029,-0.0016,-3.7e+02,-1.3e-05,-6e-05,4.6e-06,-1.7e-05,5.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,8.9e-10,3e-06,3e-06,8.9e-08,0,0,0,0,0,0,0,0 -18390000,0.71,6.1e-05,-0.013,0.71,0.014,0.00032,0.008,0.0034,-0.0012,-3.7e+02,-1.3e-05,-6e-05,4.9e-06,-1.6e-05,5.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.9e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-10,5.2e-10,8.6e-10,3e-06,3e-06,8.4e-08,0,0,0,0,0,0,0,0 -18490000,0.71,7.6e-05,-0.013,0.71,0.015,0.00077,0.0076,0.0049,-0.0011,-3.7e+02,-1.3e-05,-6e-05,5e-06,-1.6e-05,5.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,4.9e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-10,5.2e-10,8.5e-10,3e-06,3e-06,8.2e-08,0,0,0,0,0,0,0,0 -18590000,0.71,8.1e-05,-0.012,0.71,0.014,0.00095,0.0058,0.0037,-0.00098,-3.7e+02,-1.3e-05,-6e-05,5.4e-06,-1.6e-05,5.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.9e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,8.2e-10,3e-06,3e-06,7.8e-08,0,0,0,0,0,0,0,0 -18690000,0.71,5e-05,-0.012,0.71,0.014,0.00029,0.0039,0.0051,-0.00089,-3.7e+02,-1.3e-05,-6e-05,5.3e-06,-1.6e-05,5.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.8e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,8e-10,3e-06,3e-06,7.5e-08,0,0,0,0,0,0,0,0 -18790000,0.71,8.1e-05,-0.012,0.71,0.013,0.00054,0.0035,0.0039,-0.00071,-3.7e+02,-1.4e-05,-6e-05,5.1e-06,-1.6e-05,6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.8e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-10,4.3e-10,7.9e-10,3e-06,3e-06,7.2e-08,0,0,0,0,0,0,0,0 -18890000,0.71,0.0001,-0.012,0.71,0.013,0.0011,0.0042,0.0052,-0.0006,-3.7e+02,-1.4e-05,-6e-05,5.6e-06,-1.6e-05,6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-10,4.3e-10,7.7e-10,3e-06,3e-06,7e-08,0,0,0,0,0,0,0,0 -18990000,0.71,9.1e-05,-0.012,0.71,0.014,0.0019,0.0028,0.0065,-0.00051,-3.7e+02,-1.4e-05,-6e-05,5.7e-06,-1.6e-05,6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-10,3.9e-10,7.5e-10,2.9e-06,2.9e-06,6.6e-08,0,0,0,0,0,0,0,0 -19090000,0.71,7.5e-05,-0.012,0.71,0.015,0.0025,0.0058,0.008,-0.00026,-3.7e+02,-1.4e-05,-6e-05,5.7e-06,-1.6e-05,6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-10,3.9e-10,7.3e-10,2.9e-06,2.9e-06,6.5e-08,0,0,0,0,0,0,0,0 -19190000,0.71,7.7e-05,-0.012,0.71,0.015,0.0025,0.0059,0.0087,-0.00026,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.7e-05,5.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,7.2e-10,2.9e-06,2.9e-06,6.2e-08,0,0,0,0,0,0,0,0 -19290000,0.71,0.0001,-0.012,0.71,0.015,0.0018,0.0086,0.01,-2.8e-05,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.7e-05,5.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,7e-10,2.9e-06,2.9e-06,6e-08,0,0,0,0,0,0,0,0 -19390000,0.71,0.00011,-0.012,0.71,0.013,0.0008,0.012,0.0082,-9.1e-05,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.7e-05,6.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-10,3.3e-10,6.8e-10,2.9e-06,2.9e-06,5.8e-08,0,0,0,0,0,0,0,0 -19490000,0.71,0.00014,-0.012,0.71,0.012,0.00011,0.0088,0.0094,-4.9e-05,-3.7e+02,-1.4e-05,-6.1e-05,6.1e-06,-1.7e-05,6.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,6.7e-10,2.9e-06,2.9e-06,5.6e-08,0,0,0,0,0,0,0,0 -19590000,0.71,0.00018,-0.012,0.71,0.01,-0.00096,0.0081,0.0076,-0.00011,-3.7e+02,-1.4e-05,-6.1e-05,6.5e-06,-1.7e-05,6.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,6.5e-10,2.9e-06,2.9e-06,5.4e-08,0,0,0,0,0,0,0,0 -19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0031,0.0096,0.0086,-0.00032,-3.7e+02,-1.4e-05,-6.1e-05,6.3e-06,-1.7e-05,6.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,6.4e-10,2.9e-06,2.9e-06,5.2e-08,0,0,0,0,0,0,0,0 -19790000,0.71,0.00025,-0.012,0.71,0.008,-0.004,0.01,0.007,-0.00026,-3.7e+02,-1.4e-05,-6.1e-05,6.3e-06,-1.7e-05,6.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.4e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,6.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19890000,0.71,0.0002,-0.012,0.71,0.0068,-0.0043,0.011,0.0077,-0.00069,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,6.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.4e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,6.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19990000,0.71,0.00019,-0.012,0.71,0.0043,-0.005,0.014,0.0063,-0.00058,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.6e-05,7.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.4e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20090000,0.71,0.00018,-0.012,0.71,0.0041,-0.0069,0.014,0.0067,-0.0012,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-1.6e-05,7.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.0001,4.4e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-10,2.5e-10,5.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20190000,0.71,0.00028,-0.012,0.71,0.0018,-0.0076,0.017,0.0044,-0.00092,-3.7e+02,-1.4e-05,-6e-05,8e-06,-1.5e-05,7.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20290000,0.71,0.00024,-0.012,0.71,0.00064,-0.0092,0.015,0.0045,-0.0018,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-1.5e-05,7.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,5.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20390000,0.71,0.00026,-0.012,0.71,-0.0019,-0.0098,0.017,0.0026,-0.0014,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-1.3e-05,7.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20490000,0.71,0.00032,-0.012,0.71,-0.0023,-0.011,0.016,0.0024,-0.0024,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-1.3e-05,7.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20590000,0.71,0.00034,-0.012,0.71,-0.002,-0.011,0.013,0.002,-0.0019,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-1.1e-05,7.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.9e-05,9.9e-05,4.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-10,1.9e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20690000,0.71,0.00037,-0.012,0.71,-0.002,-0.012,0.015,0.0018,-0.003,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-1.1e-05,7.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-10,1.9e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20790000,0.71,0.00039,-0.012,0.71,-0.0031,-0.011,0.015,0.0015,-0.0024,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-9.5e-06,7.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.8e-05,9.7e-05,4.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20890000,0.71,0.00038,-0.012,0.71,-0.0035,-0.013,0.014,0.0012,-0.0036,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-9.6e-06,7.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.8e-05,9.8e-05,4.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20990000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.015,0.0028,-0.003,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-7.6e-06,7.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.6e-05,9.6e-05,4.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.9e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21090000,0.71,0.00038,-0.012,0.71,-0.0039,-0.017,0.015,0.0024,-0.0045,-3.7e+02,-1.4e-05,-6e-05,8.2e-06,-7.6e-06,7.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.7e-05,9.7e-05,4.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.8e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21190000,0.71,0.00042,-0.012,0.71,-0.0032,-0.015,0.014,0.0039,-0.0036,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-5.3e-06,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.5e-05,9.5e-05,4e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.5e-10,4.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21290000,0.71,0.00046,-0.012,0.71,-0.0037,-0.018,0.016,0.0035,-0.0053,-3.7e+02,-1.4e-05,-6e-05,8.4e-06,-5.3e-06,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.6e-05,9.5e-05,4e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-10,1.5e-10,4.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21390000,0.71,0.0005,-0.012,0.71,-0.0046,-0.017,0.016,0.003,-0.0033,-3.7e+02,-1.4e-05,-6e-05,8.2e-06,-1.6e-06,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.4e-05,9.4e-05,4e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,4.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21490000,0.71,0.00051,-0.012,0.71,-0.0051,-0.018,0.015,0.0025,-0.005,-3.7e+02,-1.4e-05,-6e-05,8.3e-06,-1.6e-06,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.4e-05,9.4e-05,4e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,4.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21590000,0.71,0.00053,-0.012,0.71,-0.0056,-0.015,0.015,0.002,-0.003,-3.7e+02,-1.4e-05,-6e-05,8.2e-06,1.8e-06,7.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.3e-05,9.3e-05,3.9e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,4.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21690000,0.71,0.00054,-0.012,0.71,-0.0055,-0.016,0.017,0.0015,-0.0046,-3.7e+02,-1.4e-05,-6e-05,8.3e-06,1.8e-06,7.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.3e-05,9.3e-05,3.9e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,4.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21790000,0.71,0.00056,-0.012,0.71,-0.0061,-0.011,0.015,0.00019,-0.00063,-3.7e+02,-1.4e-05,-5.9e-05,8e-06,7.1e-06,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.2e-05,9.2e-05,3.9e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-10,1.2e-10,4.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21890000,0.71,0.00056,-0.012,0.71,-0.0061,-0.012,0.016,-0.00042,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,8e-06,7e-06,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.2e-05,9.2e-05,3.9e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,4.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21990000,0.71,0.00061,-0.012,0.71,-0.0066,-0.0089,0.016,-0.0014,0.0016,-3.7e+02,-1.4e-05,-5.9e-05,7.9e-06,1.1e-05,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.1e-05,9.1e-05,3.9e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22090000,0.71,0.00063,-0.012,0.71,-0.0069,-0.008,0.015,-0.002,0.00076,-3.7e+02,-1.4e-05,-5.9e-05,7.8e-06,1.1e-05,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.1e-05,9.1e-05,3.8e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22190000,0.71,0.0006,-0.012,0.71,-0.0068,-0.0072,0.015,-0.0017,0.0007,-3.7e+02,-1.4e-05,-5.9e-05,7.8e-06,1.2e-05,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,9e-05,3.8e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22290000,0.71,0.00064,-0.012,0.71,-0.0081,-0.0079,0.015,-0.0024,-6.4e-05,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.2e-05,7.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,9e-05,3.8e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22390000,0.71,0.00061,-0.012,0.71,-0.0087,-0.0074,0.017,-0.0021,-7.2e-05,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.3e-05,7.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.9e-05,8.9e-05,3.8e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22490000,0.71,0.00062,-0.012,0.71,-0.0093,-0.0073,0.018,-0.003,-0.00083,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.3e-05,7.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,8.9e-05,3.7e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22590000,0.71,0.0006,-0.012,0.71,-0.0091,-0.0068,0.017,-0.0033,0.00024,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,1.4e-05,7.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.7e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22690000,0.71,0.00063,-0.012,0.71,-0.01,-0.0066,0.018,-0.0042,-0.00043,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.4e-05,7.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.9e-05,8.9e-05,3.7e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0054,0.019,-0.0054,-0.00034,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.5e-05,7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.7e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.005,0.021,-0.0065,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,1.5e-05,7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.6e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0055,0.022,-0.0073,-0.00077,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.5e-05,6.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.7e-05,3.6e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23090000,0.71,0.00057,-0.012,0.71,-0.013,-0.0055,0.022,-0.0086,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.5e-05,6.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.7e-05,3.6e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23190000,0.71,0.00064,-0.012,0.71,-0.014,-0.0064,0.024,-0.012,-0.0012,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.6e-05,7.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.6e-05,3.6e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0077,0.024,-0.013,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.6e-05,7.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.7e-05,3.6e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.0079,0.022,-0.016,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.7e-05,7.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.6e-05,8.6e-05,3.5e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0088,-0.012,-0.018,-0.0025,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.7e-05,7.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.6e-05,3.5e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23590000,0.71,0.0083,-0.0018,0.71,-0.033,-0.0075,-0.044,-0.016,-0.0012,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.9e-05,7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.7e-05,8.5e-05,3.5e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0023,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.9e-05,7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.8e-05,8.5e-05,3.5e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23790000,0.71,0.005,0.00064,0.71,-0.088,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.1e-05,6.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.6e-05,8.4e-05,3.5e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.0049,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.1e-05,6.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.6e-05,8.5e-05,3.4e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.039,-0.25,-0.034,-0.0081,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.2e-05,6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.4e-05,3.4e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.2e-05,6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.5e-05,8.4e-05,3.4e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-11,6.7e-11,2.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.4e-05,5.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.4e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.4e-05,5.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.5e-05,8.4e-05,3.4e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-11,6.4e-11,2.7e-10,2.8e-06,2.8e-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.5e-06,2.1e-05,5.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2.1e-05,5.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.3e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24590000,0.71,0.0051,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.6e-06,2e-05,4.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.7e-06,2e-05,4.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.3e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2.4e-05,3.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24890000,0.71,0.0066,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2.4e-05,3.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.2e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -24990000,0.71,0.0084,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,3.2e-05,2.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.4e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25090000,0.71,0.0087,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,3.3e-05,2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.2e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2.9e-05,1.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.2e-05,8e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.3e-11,5.2e-11,2.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2.9e-05,1.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8e-05,3.2e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,6.2e-06,3e-05,-2.7e-08,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,7.9e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6.3e-06,3e-05,7.4e-08,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,7.9e-05,3.2e-05,0.019,0.018,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6.3e-06,2.7e-05,-8.9e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.2e-05,7.8e-05,3.1e-05,0.017,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6.4e-06,2.7e-05,-8.7e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.4e-05,7.9e-05,3.1e-05,0.019,0.018,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6.5e-06,3.4e-05,-3.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.4e-05,7.8e-05,3.1e-05,0.018,0.016,0.0079,0.04,0.04,0.035,4.8e-11,4.7e-11,2.2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25890000,0.7,0.017,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.7e-06,3.4e-05,-3.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.5e-05,7.8e-05,3.1e-05,0.02,0.018,0.008,0.044,0.044,0.035,4.8e-11,4.8e-11,2.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -25990000,0.7,0.016,0.025,0.71,-0.65,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.8e-06,3e-05,-5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0035,8.2e-05,7.7e-05,3.1e-05,0.019,0.017,0.0079,0.04,0.04,0.035,4.7e-11,4.6e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,6.6e-06,3e-05,-4.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0035,8.5e-05,7.7e-05,3.1e-05,0.021,0.018,0.008,0.044,0.044,0.035,4.7e-11,4.6e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6.8e-06,4.2e-05,-8.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0034,8.6e-05,7.7e-05,3e-05,0.02,0.017,0.0079,0.04,0.04,0.035,4.6e-11,4.5e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26290000,0.7,0.024,0.047,0.71,-0.86,-0.44,-1.3,-0.61,-0.47,-3.7e+02,-1.1e-05,-5.9e-05,6.8e-06,4.2e-05,-8.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0034,8.7e-05,7.7e-05,3e-05,0.023,0.018,0.008,0.044,0.044,0.035,4.6e-11,4.5e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26390000,0.7,0.023,0.044,0.71,-0.94,-0.5,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,7e-06,2.9e-05,-9.8e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0033,8.4e-05,7.6e-05,3e-05,0.022,0.017,0.0079,0.04,0.04,0.035,4.5e-11,4.4e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26490000,0.7,0.03,0.059,0.71,-1,-0.54,-1.3,-0.77,-0.6,-3.7e+02,-1e-05,-5.9e-05,7.1e-06,2.9e-05,-9.8e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0033,9.1e-05,7.6e-05,3e-05,0.025,0.019,0.008,0.045,0.044,0.035,4.5e-11,4.4e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26590000,0.7,0.036,0.075,0.71,-1.1,-0.6,-1.3,-0.82,-0.67,-3.7e+02,-9.7e-06,-5.9e-05,6.9e-06,4e-05,-0.00013,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0031,9.5e-05,7.6e-05,3e-05,0.024,0.017,0.008,0.04,0.039,0.035,4.4e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26690000,0.7,0.037,0.078,0.71,-1.3,-0.66,-1.3,-0.94,-0.73,-3.7e+02,-9.7e-06,-5.9e-05,7.2e-06,3.9e-05,-0.00013,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0031,9.7e-05,7.6e-05,3e-05,0.029,0.019,0.008,0.045,0.044,0.035,4.4e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26790000,0.7,0.035,0.073,0.71,-1.4,-0.75,-1.3,-1,-0.86,-3.7e+02,-9.3e-06,-6e-05,7.3e-06,1.9e-05,-0.00015,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0029,9.1e-05,7.5e-05,3e-05,0.028,0.018,0.008,0.041,0.039,0.035,4.4e-11,4.2e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26890000,0.7,0.044,0.095,0.71,-1.5,-0.81,-1.3,-1.2,-0.94,-3.7e+02,-9.3e-06,-6e-05,7.6e-06,1.8e-05,-0.00015,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0001,7.6e-05,3e-05,0.033,0.021,0.0081,0.046,0.044,0.035,4.4e-11,4.2e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26990000,0.69,0.049,0.12,0.71,-1.6,-0.91,-1.3,-1.2,-1,-3.7e+02,-8.5e-06,-5.9e-05,7.9e-06,3.2e-05,-0.00019,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.00011,7.7e-05,3e-05,0.032,0.02,0.0081,0.041,0.04,0.035,4.3e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27090000,0.69,0.05,0.12,0.71,-1.8,-1,-1.3,-1.4,-1.1,-3.7e+02,-8.4e-06,-5.9e-05,8.3e-06,3.1e-05,-0.0002,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.00011,7.7e-05,3e-05,0.039,0.022,0.0082,0.046,0.044,0.035,4.3e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27190000,0.7,0.047,0.11,0.71,-2.1,-1.1,-1.2,-1.6,-1.2,-3.7e+02,-8.3e-06,-5.9e-05,8.7e-06,4e-05,-0.0002,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.8e-05,7.6e-05,3e-05,0.04,0.023,0.0082,0.049,0.046,0.035,4.3e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27290000,0.7,0.042,0.094,0.71,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-8.3e-06,-5.9e-05,9e-06,3.9e-05,-0.0002,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.2e-05,7.5e-05,3e-05,0.046,0.025,0.0082,0.056,0.051,0.035,4.3e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27390000,0.7,0.036,0.078,0.71,-2.3,-1.2,-1.2,-2,-1.4,-3.7e+02,-7.9e-06,-5.8e-05,9.5e-06,6.3e-05,-0.00021,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0021,8.3e-05,7.4e-05,2.9e-05,0.043,0.025,0.0082,0.057,0.054,0.035,4.3e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27490000,0.7,0.03,0.063,0.71,-2.4,-1.2,-1.2,-2.2,-1.5,-3.7e+02,-7.8e-06,-5.8e-05,9.8e-06,6.2e-05,-0.00021,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0021,8e-05,7.4e-05,2.9e-05,0.047,0.027,0.0083,0.065,0.059,0.035,4.3e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27590000,0.7,0.026,0.05,0.71,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.7e-06,-5.8e-05,1e-05,5.6e-05,-0.00021,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0018,7.7e-05,7.4e-05,2.9e-05,0.041,0.025,0.0082,0.067,0.062,0.035,4.3e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27690000,0.7,0.025,0.049,0.71,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.7e-06,-5.8e-05,1e-05,5.5e-05,-0.00021,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0018,7.6e-05,7.4e-05,2.9e-05,0.043,0.027,0.0083,0.075,0.068,0.035,4.3e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27790000,0.71,0.026,0.05,0.71,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,1e-05,5.5e-05,-0.0002,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0016,7.6e-05,7.4e-05,2.8e-05,0.038,0.026,0.0083,0.076,0.07,0.035,4.3e-11,4e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27890000,0.71,0.025,0.048,0.71,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,1e-05,5.3e-05,-0.0002,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0016,7.6e-05,7.4e-05,2.8e-05,0.04,0.028,0.0084,0.085,0.077,0.036,4.3e-11,4e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27990000,0.71,0.024,0.044,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-7.6e-06,-5.8e-05,1e-05,4.4e-05,-0.0002,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0014,7.5e-05,7.4e-05,2.8e-05,0.035,0.026,0.0083,0.085,0.079,0.035,4.3e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-7.6e-06,-5.8e-05,9.7e-06,4.4e-05,-0.00019,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0014,7.6e-05,7.4e-05,2.8e-05,0.037,0.028,0.0084,0.095,0.087,0.035,4.3e-11,4e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-7.6e-06,-5.8e-05,9.6e-06,3.9e-05,-0.00019,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,7.3e-05,2.8e-05,0.033,0.026,0.0084,0.095,0.088,0.035,4.3e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28290000,0.71,0.027,0.054,0.7,-2.8,-1.3,-0.087,-4.5,-2.4,-3.7e+02,-7.6e-06,-5.8e-05,9.3e-06,3.8e-05,-0.00018,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.5e-05,7.4e-05,2.8e-05,0.034,0.027,0.0086,0.1,0.096,0.036,4.3e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28390000,0.71,0.011,0.022,0.7,-2.8,-1.3,0.77,-4.8,-2.6,-3.7e+02,-7.6e-06,-5.8e-05,9.1e-06,3.5e-05,-0.00018,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.5e-05,7.4e-05,2.8e-05,0.035,0.028,0.0087,0.11,0.1,0.036,4.3e-11,3.9e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28490000,0.71,0.0021,0.0042,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-7.6e-06,-5.8e-05,8.9e-06,3.3e-05,-0.00017,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,7.5e-05,2.7e-05,0.035,0.029,0.0088,0.13,0.11,0.036,4.3e-11,3.9e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28590000,0.71,0.00035,0.00071,0.7,-2.7,-1.3,0.96,-5.3,-2.8,-3.7e+02,-7.6e-06,-5.8e-05,8.8e-06,3e-05,-0.00016,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.5e-05,2.7e-05,0.035,0.03,0.0089,0.14,0.12,0.036,4.4e-11,4e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28690000,0.71,-0.00036,-0.00021,0.7,-2.6,-1.2,0.97,-5.6,-2.9,-3.7e+02,-7.6e-06,-5.8e-05,8.7e-06,2.6e-05,-0.00015,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.5e-05,2.7e-05,0.035,0.032,0.009,0.15,0.13,0.036,4.4e-11,4e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28790000,0.71,-0.00085,-0.00057,0.7,-2.6,-1.2,0.97,-5.9,-3,-3.7e+02,-7.8e-06,-5.8e-05,8.4e-06,-5.3e-06,-0.00022,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.5e-05,2.7e-05,0.031,0.029,0.0089,0.15,0.13,0.036,4.3e-11,3.9e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28890000,0.71,-0.00087,-0.00036,0.7,-2.5,-1.2,0.96,-6.2,-3.1,-3.7e+02,-7.8e-06,-5.8e-05,8.2e-06,-9.1e-06,-0.00021,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.5e-05,2.7e-05,0.031,0.03,0.009,0.16,0.14,0.036,4.4e-11,3.9e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28990000,0.72,-0.00085,-1.5e-05,0.7,-2.5,-1.2,0.95,-6.5,-3.2,-3.7e+02,-8.2e-06,-5.8e-05,7.7e-06,-2.6e-05,-0.00029,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.5e-05,2.7e-05,0.028,0.028,0.009,0.16,0.14,0.036,4.3e-11,3.9e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29090000,0.72,-0.0007,0.00037,0.7,-2.4,-1.1,0.94,-6.8,-3.4,-3.7e+02,-8.2e-06,-5.8e-05,7.4e-06,-3e-05,-0.00028,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.7e-05,0.029,0.029,0.009,0.17,0.15,0.036,4.3e-11,3.9e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29190000,0.72,-0.00056,0.00074,0.7,-2.4,-1.1,0.94,-7.1,-3.5,-3.7e+02,-8.5e-06,-5.8e-05,7.1e-06,-4.3e-05,-0.0003,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.7e-05,0.027,0.028,0.009,0.17,0.15,0.036,4.3e-11,3.9e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29290000,0.72,-0.0002,0.0016,0.7,-2.3,-1.1,0.96,-7.3,-3.6,-3.7e+02,-8.5e-06,-5.8e-05,6.7e-06,-4.8e-05,-0.00029,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.6e-05,0.027,0.029,0.0091,0.18,0.16,0.036,4.3e-11,3.9e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29390000,0.72,0.0003,0.003,0.7,-2.3,-1.1,0.97,-7.6,-3.7,-3.7e+02,-8.9e-06,-5.8e-05,6.1e-06,-5.5e-05,-0.00032,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.025,0.027,0.009,0.17,0.16,0.036,4.3e-11,3.8e-11,1.4e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -29490000,0.72,0.00082,0.0041,0.7,-2.3,-1.1,0.97,-7.9,-3.8,-3.7e+02,-8.9e-06,-5.8e-05,5.8e-06,-5.9e-05,-0.00031,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.026,0.028,0.0091,0.19,0.17,0.037,4.3e-11,3.8e-11,1.4e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -29590000,0.72,0.0012,0.0052,0.7,-2.2,-1.1,0.96,-8.1,-3.9,-3.7e+02,-9.2e-06,-5.8e-05,5.4e-06,-7.6e-05,-0.00031,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.025,0.027,0.009,0.18,0.17,0.036,4.2e-11,3.8e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -29690000,0.72,0.0015,0.0058,0.7,-2.2,-1.1,0.95,-8.3,-4,-3.7e+02,-9.2e-06,-5.8e-05,5e-06,-8e-05,-0.0003,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.028,0.0091,0.2,0.18,0.036,4.2e-11,3.8e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -29790000,0.72,0.0018,0.0063,0.7,-2.2,-1.1,0.94,-8.6,-4.1,-3.7e+02,-9.5e-06,-5.8e-05,4.7e-06,-9e-05,-0.00031,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.025,0.026,0.0091,0.19,0.18,0.037,4.2e-11,3.8e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -29890000,0.72,0.0018,0.0065,0.7,-2.1,-1.1,0.93,-8.8,-4.2,-3.7e+02,-9.5e-06,-5.8e-05,4.2e-06,-9.7e-05,-0.00029,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.21,0.19,0.037,4.2e-11,3.8e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -29990000,0.72,0.002,0.0067,0.7,-2.1,-1,0.91,-9.1,-4.3,-3.7e+02,-9.8e-06,-5.8e-05,3.8e-06,-0.00011,-0.00028,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.025,0.026,0.009,0.2,0.19,0.036,4.1e-11,3.7e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30090000,0.72,0.002,0.0066,0.7,-2.1,-1,0.89,-9.3,-4.4,-3.7e+02,-9.8e-06,-5.8e-05,3.4e-06,-0.00012,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.22,0.2,0.036,4.1e-11,3.7e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30190000,0.72,0.002,0.0065,0.7,-2.1,-1,0.88,-9.6,-4.5,-3.7e+02,-1e-05,-5.8e-05,3.1e-06,-0.00013,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.5e-05,2.6e-05,0.025,0.026,0.009,0.21,0.2,0.037,4.1e-11,3.7e-11,1.3e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30290000,0.72,0.0019,0.0063,0.7,-2,-1,0.87,-9.8,-4.6,-3.7e+02,-1e-05,-5.8e-05,2.7e-06,-0.00013,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.22,0.21,0.037,4.1e-11,3.7e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30390000,0.72,0.0019,0.0061,0.7,-2,-1,0.85,-10,-4.7,-3.7e+02,-1e-05,-5.8e-05,2.3e-06,-0.00014,-0.00026,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.6e-05,0.025,0.026,0.009,0.22,0.21,0.036,4e-11,3.7e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30490000,0.72,0.0018,0.0059,0.7,-2,-1,0.84,-10,-4.8,-3.7e+02,-1e-05,-5.8e-05,2.1e-06,-0.00014,-0.00025,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.6e-05,0.026,0.027,0.0091,0.23,0.22,0.037,4e-11,3.7e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30590000,0.72,0.0018,0.0056,0.7,-1.9,-1,0.8,-10,-4.9,-3.7e+02,-1.1e-05,-5.8e-05,1.8e-06,-0.00015,-0.00024,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.025,0.025,0.009,0.23,0.22,0.037,4e-11,3.6e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30690000,0.72,0.0016,0.0052,0.7,-1.9,-1,0.79,-11,-5,-3.7e+02,-1.1e-05,-5.8e-05,1.5e-06,-0.00015,-0.00023,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.027,0.027,0.009,0.24,0.23,0.037,4e-11,3.6e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -30790000,0.72,0.0016,0.0049,0.7,-1.9,-0.99,0.78,-11,-5.1,-3.7e+02,-1.1e-05,-5.8e-05,1.1e-06,-0.00016,-0.00023,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.026,0.025,0.0089,0.24,0.23,0.037,3.9e-11,3.6e-11,1.2e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -30890000,0.72,0.0014,0.0045,0.7,-1.9,-0.98,0.77,-11,-5.2,-3.7e+02,-1.1e-05,-5.8e-05,8.4e-07,-0.00016,-0.00022,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.027,0.027,0.009,0.25,0.24,0.037,3.9e-11,3.6e-11,1.2e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -30990000,0.72,0.0014,0.004,0.7,-1.8,-0.97,0.76,-11,-5.3,-3.7e+02,-1.1e-05,-5.8e-05,5e-07,-0.00016,-0.00021,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.026,0.025,0.0089,0.25,0.24,0.036,3.8e-11,3.6e-11,1.2e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31090000,0.72,0.0012,0.0035,0.7,-1.8,-0.96,0.75,-11,-5.4,-3.7e+02,-1.1e-05,-5.8e-05,2.1e-07,-0.00017,-0.0002,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.027,0.026,0.0089,0.26,0.25,0.037,3.8e-11,3.6e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31190000,0.72,0.0012,0.0033,0.7,-1.8,-0.96,0.74,-12,-5.4,-3.7e+02,-1.1e-05,-5.8e-05,-7.9e-08,-0.00018,-0.00017,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.026,0.025,0.0088,0.26,0.25,0.037,3.8e-11,3.5e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31290000,0.72,0.00094,0.0027,0.7,-1.8,-0.95,0.74,-12,-5.5,-3.7e+02,-1.1e-05,-5.8e-05,-3.2e-07,-0.00019,-0.00016,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.028,0.026,0.0089,0.27,0.26,0.037,3.8e-11,3.5e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31390000,0.72,0.00087,0.0023,0.7,-1.7,-0.94,0.73,-12,-5.6,-3.7e+02,-1.2e-05,-5.8e-05,-6.1e-07,-0.00019,-0.00014,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.026,0.025,0.0087,0.27,0.26,0.036,3.7e-11,3.5e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31490000,0.72,0.00065,0.0016,0.7,-1.7,-0.93,0.73,-12,-5.7,-3.7e+02,-1.2e-05,-5.8e-05,-9.1e-07,-0.0002,-0.00013,-0.00099,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.028,0.026,0.0088,0.28,0.27,0.037,3.7e-11,3.5e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31590000,0.72,0.00064,0.0013,0.7,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.2e-05,-5.7e-05,-1.1e-06,-0.0002,-0.00011,-0.00099,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.027,0.025,0.0087,0.28,0.27,0.037,3.6e-11,3.4e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31690000,0.72,0.00038,0.00064,0.7,-1.6,-0.91,0.73,-13,-5.9,-3.7e+02,-1.2e-05,-5.7e-05,-1.3e-06,-0.00021,-0.0001,-0.00098,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.028,0.026,0.0087,0.29,0.28,0.037,3.6e-11,3.5e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31790000,0.71,0.00026,2.8e-05,0.7,-1.6,-0.9,0.73,-13,-6,-3.7e+02,-1.2e-05,-5.7e-05,-1.5e-06,-0.00022,-8.2e-05,-0.00098,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.027,0.025,0.0087,0.29,0.27,0.037,3.5e-11,3.4e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31890000,0.71,6.7e-06,-0.00068,0.7,-1.6,-0.89,0.72,-13,-6.1,-3.7e+02,-1.2e-05,-5.7e-05,-1.7e-06,-0.00022,-7e-05,-0.00097,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.029,0.026,0.0087,0.3,0.29,0.037,3.5e-11,3.4e-11,1.1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -31990000,0.71,-7.8e-05,-0.0011,0.7,-1.6,-0.88,0.72,-13,-6.2,-3.7e+02,-1.2e-05,-5.7e-05,-2e-06,-0.00023,-5.2e-05,-0.00097,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.027,0.025,0.0086,0.3,0.28,0.036,3.5e-11,3.4e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32090000,0.71,-0.00038,-0.0019,0.7,-1.5,-0.87,0.72,-13,-6.2,-3.7e+02,-1.2e-05,-5.7e-05,-2.2e-06,-0.00024,-3.7e-05,-0.00096,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.029,0.026,0.0087,0.31,0.3,0.037,3.5e-11,3.4e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32190000,0.71,-0.00051,-0.0026,0.7,-1.5,-0.86,0.72,-13,-6.3,-3.7e+02,-1.3e-05,-5.7e-05,-2.5e-06,-0.00024,-1.7e-05,-0.00095,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0085,0.31,0.29,0.036,3.4e-11,3.3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32290000,0.71,-0.00075,-0.0034,0.7,-1.5,-0.85,0.71,-14,-6.4,-3.7e+02,-1.3e-05,-5.7e-05,-2.7e-06,-0.00025,-1.4e-06,-0.00095,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.2e-05,7.3e-05,2.4e-05,0.029,0.026,0.0086,0.32,0.31,0.036,3.4e-11,3.3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32390000,0.71,-0.00089,-0.004,0.7,-1.5,-0.84,0.71,-14,-6.5,-3.7e+02,-1.3e-05,-5.7e-05,-2.8e-06,-0.00025,7.2e-06,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0085,0.32,0.3,0.037,3.3e-11,3.3e-11,1e-10,2.6e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -32490000,0.71,-0.001,-0.0042,0.7,-1.4,-0.82,0.72,-14,-6.6,-3.7e+02,-1.3e-05,-5.7e-05,-2.9e-06,-0.00026,1.8e-05,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.03,0.026,0.0085,0.33,0.32,0.037,3.3e-11,3.3e-11,1e-10,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -32590000,0.71,-0.00094,-0.0044,0.7,-1.4,-0.81,0.72,-14,-6.7,-3.7e+02,-1.3e-05,-5.7e-05,-3.1e-06,-0.00026,2.6e-05,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0084,0.33,0.31,0.036,3.3e-11,3.2e-11,9.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -32690000,0.71,-0.00099,-0.0045,0.7,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.3e-05,-5.7e-05,-3.2e-06,-0.00026,3.2e-05,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.03,0.026,0.0085,0.34,0.32,0.036,3.3e-11,3.2e-11,9.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -32790000,0.71,-0.0009,-0.0045,0.7,-1.3,-0.79,0.71,-14,-6.8,-3.7e+02,-1.3e-05,-5.7e-05,-3.4e-06,-0.00027,4.1e-05,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.1e-05,7.2e-05,2.3e-05,0.028,0.025,0.0084,0.34,0.32,0.036,3.2e-11,3.2e-11,9.7e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -32890000,0.71,-0.00081,-0.0044,0.7,-1.3,-0.78,0.71,-14,-6.9,-3.7e+02,-1.3e-05,-5.7e-05,-3.6e-06,-0.00027,5.1e-05,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.1e-05,7.2e-05,2.3e-05,0.03,0.026,0.0084,0.35,0.33,0.036,3.2e-11,3.2e-11,9.6e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -32990000,0.71,-0.00061,-0.0044,0.7,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-1.3e-05,-5.7e-05,-3.6e-06,-0.00028,6.5e-05,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.1e-05,7.2e-05,2.3e-05,0.028,0.025,0.0083,0.35,0.33,0.036,3.1e-11,3.2e-11,9.5e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33090000,0.71,-0.00065,-0.0044,0.7,-1.3,-0.76,0.7,-15,-7.1,-3.7e+02,-1.3e-05,-5.7e-05,-3.6e-06,-0.00028,7e-05,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.1e-05,7.2e-05,2.3e-05,0.03,0.026,0.0084,0.36,0.34,0.036,3.1e-11,3.2e-11,9.4e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33190000,0.71,0.0028,-0.0034,0.71,-1.2,-0.75,0.64,-15,-7.1,-3.7e+02,-1.3e-05,-5.7e-05,-3.7e-06,-0.00028,7.8e-05,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8e-05,7.2e-05,2.3e-05,0.028,0.025,0.0083,0.36,0.34,0.036,3.1e-11,3.1e-11,9.3e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33290000,0.66,0.015,-0.0025,0.76,-1.2,-0.73,0.62,-15,-7.2,-3.7e+02,-1.3e-05,-5.7e-05,-3.7e-06,-0.00029,8.2e-05,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,7.9e-05,7.3e-05,2.5e-05,0.03,0.026,0.0083,0.37,0.35,0.036,3.1e-11,3.1e-11,9.2e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33390000,0.55,0.013,-0.0027,0.83,-1.2,-0.72,0.81,-15,-7.3,-3.7e+02,-1.4e-05,-5.7e-05,-3.7e-06,-0.00029,9.2e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.00091,7.8e-05,7.3e-05,5.2e-05,0.028,0.025,0.0083,0.37,0.35,0.036,3e-11,3.1e-11,9.2e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33490000,0.41,0.0061,-0.00013,0.91,-1.2,-0.71,0.83,-15,-7.3,-3.7e+02,-1.4e-05,-5.7e-05,-3.8e-06,-0.00029,9.3e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.00083,7.7e-05,7.5e-05,0.00012,0.03,0.026,0.0081,0.38,0.36,0.036,3e-11,3.1e-11,9.1e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33590000,0.26,0.00013,-0.0025,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,-0.00029,9.3e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.00068,7.5e-05,7.6e-05,0.00023,0.029,0.026,0.0078,0.38,0.36,0.036,3e-11,3e-11,9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33690000,0.09,-0.0033,-0.0054,1,-1.1,-0.71,0.8,-16,-7.5,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,-0.00029,9.3e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.00051,7.4e-05,7.8e-05,0.00035,0.032,0.029,0.0076,0.39,0.37,0.036,2.9e-11,3e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33790000,-0.081,-0.0048,-0.0071,1,-1.1,-0.69,0.78,-16,-7.5,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,-0.00029,9.3e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.00032,7.1e-05,7.8e-05,0.00042,0.031,0.029,0.0074,0.38,0.36,0.036,2.9e-11,2.9e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33890000,-0.25,-0.0059,-0.0077,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,-0.00029,9.3e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7e-05,7.9e-05,0.00043,0.035,0.032,0.0072,0.39,0.38,0.036,2.8e-11,2.9e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -33990000,-0.39,-0.0041,-0.011,0.92,-0.96,-0.63,0.74,-16,-7.7,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,-0.00029,9.3e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,6.7e-05,7.6e-05,0.00039,0.034,0.032,0.007,0.38,0.37,0.035,2.8e-11,2.8e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34090000,-0.5,-0.003,-0.013,0.87,-0.9,-0.58,0.74,-16,-7.7,-3.7e+02,-1.4e-05,-5.7e-05,-3.9e-06,-0.00029,9.2e-05,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,4.8e-05,6.7e-05,7.5e-05,0.00034,0.038,0.037,0.0069,0.39,0.38,0.036,2.8e-11,2.8e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34190000,-0.57,-0.0023,-0.011,0.82,-0.89,-0.54,0.74,-16,-7.8,-3.7e+02,-1.4e-05,-5.7e-05,-3.8e-06,-0.00032,0.00011,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,6.3e-05,7.1e-05,0.00028,0.038,0.037,0.0067,0.39,0.38,0.035,2.7e-11,2.8e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34290000,-0.61,-0.0032,-0.0086,0.79,-0.84,-0.49,0.74,-16,-7.9,-3.7e+02,-1.4e-05,-5.7e-05,-3.8e-06,-0.00032,0.00011,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,6.4e-05,7e-05,0.00024,0.043,0.043,0.0066,0.4,0.39,0.035,2.7e-11,2.8e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34390000,-0.64,-0.0033,-0.0061,0.77,-0.83,-0.45,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,-3.8e-06,-0.00037,0.00016,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,5.9e-05,6.5e-05,0.00021,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34490000,-0.65,-0.0042,-0.0039,0.76,-0.77,-0.41,0.73,-16,-8,-3.7e+02,-1.5e-05,-5.7e-05,-3.8e-06,-0.00037,0.00016,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.9e-05,6.5e-05,0.00018,0.049,0.05,0.0064,0.41,0.4,0.035,2.7e-11,2.7e-11,8.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34590000,-0.66,-0.0035,-0.0028,0.75,-0.78,-0.39,0.73,-17,-8,-3.7e+02,-1.5e-05,-5.7e-05,-3.7e-06,-0.00047,0.00025,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.4e-05,5.9e-05,0.00016,0.047,0.048,0.0063,0.4,0.4,0.034,2.7e-11,2.7e-11,8.9e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -34690000,-0.67,-0.0039,-0.0021,0.74,-0.72,-0.35,0.73,-17,-8.1,-3.7e+02,-1.5e-05,-5.7e-05,-3.7e-06,-0.00047,0.00025,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.4e-05,5.9e-05,0.00015,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,8.9e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -34790000,-0.67,-0.0027,-0.0018,0.74,-0.73,-0.34,0.72,-17,-8.2,-3.7e+02,-1.5e-05,-5.7e-05,-3.6e-06,-0.00059,0.00036,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,4.9e-05,5.3e-05,0.00013,0.051,0.052,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,8.9e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -34890000,-0.68,-0.0028,-0.0017,0.74,-0.68,-0.31,0.72,-17,-8.2,-3.7e+02,-1.5e-05,-5.7e-05,-3.6e-06,-0.00059,0.00036,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.9e-05,5.3e-05,0.00012,0.058,0.06,0.0062,0.42,0.42,0.034,2.7e-11,2.7e-11,8.9e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -34990000,-0.68,-0.009,-0.0045,0.73,0.33,0.3,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-3.6e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,0.00011,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,8.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35090000,-0.68,-0.009,-0.0046,0.73,0.45,0.33,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-3.5e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,0.0001,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,8.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35190000,-0.68,-0.009,-0.0046,0.73,0.48,0.36,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.5e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,9.7e-05,0.067,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35290000,-0.68,-0.0091,-0.0047,0.73,0.5,0.39,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.5e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,9.1e-05,0.072,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35390000,-0.68,-0.0091,-0.0046,0.73,0.52,0.43,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.5e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,8.6e-05,0.078,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35490000,-0.68,-0.0092,-0.0046,0.73,0.54,0.46,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,-3.6e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,8.1e-05,0.084,0.086,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35590000,-0.68,-0.006,-0.0046,0.73,0.43,0.37,-0.19,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.3e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.8e-05,4.1e-05,7.6e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35690000,-0.68,-0.006,-0.0046,0.73,0.45,0.4,-0.19,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.3e-06,-0.00073,0.00051,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.8e-05,4.1e-05,7.3e-05,0.072,0.074,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35790000,-0.68,-0.0037,-0.0045,0.73,0.37,0.34,-0.19,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.1e-06,-0.00075,0.00052,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.3e-05,3.5e-05,6.9e-05,0.06,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35890000,-0.68,-0.0037,-0.0046,0.73,0.39,0.37,-0.19,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3.1e-06,-0.00075,0.00052,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,3.3e-05,3.5e-05,6.6e-05,0.066,0.067,0.0058,0.5,0.5,0.033,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -35990000,-0.68,-0.0018,-0.0045,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-3e-06,-0.00082,0.00059,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,2.9e-05,3.1e-05,6.3e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.7e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36090000,-0.68,-0.0019,-0.0045,0.73,0.34,0.33,-0.19,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,-3e-06,-0.00082,0.00059,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,2.9e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36190000,-0.68,-0.00038,-0.0044,0.73,0.28,0.28,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-2.9e-06,-0.00093,0.00068,-0.00091,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.6e-05,2.7e-05,5.8e-05,0.054,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36290000,-0.68,-0.00049,-0.0043,0.73,0.29,0.3,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-2.9e-06,-0.00093,0.00068,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.6e-05,2.7e-05,5.6e-05,0.06,0.061,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -36390000,-0.68,0.00062,-0.0043,0.73,0.24,0.26,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,-2.8e-06,-0.0011,0.00078,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.3e-05,2.5e-05,5.4e-05,0.053,0.054,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,9.1e-11,2.3e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 -36490000,-0.68,0.00054,-0.0043,0.73,0.25,0.27,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,-2.7e-06,-0.0011,0.00078,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.3e-05,2.5e-05,5.2e-05,0.058,0.06,0.0055,0.52,0.52,0.032,2.8e-11,2.8e-11,9.1e-11,2.3e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 -36590000,-0.68,0.0014,-0.0042,0.73,0.21,0.24,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.7e-06,-0.0012,0.00088,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.1e-05,2.3e-05,5e-05,0.052,0.053,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,9.1e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 -36690000,-0.68,0.0014,-0.0042,0.73,0.21,0.25,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.7e-06,-0.0012,0.00088,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.2e-05,2.3e-05,4.9e-05,0.058,0.059,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,9.1e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0 -36790000,-0.68,0.002,-0.0041,0.73,0.18,0.22,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.6e-06,-0.0013,0.00098,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,2e-05,2.1e-05,4.7e-05,0.051,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,9.1e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -36890000,-0.68,0.0019,-0.0041,0.73,0.18,0.23,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.6e-06,-0.0013,0.00098,-0.00092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,2e-05,2.1e-05,4.6e-05,0.057,0.058,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,9.1e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -36990000,-0.68,0.0024,-0.0039,0.73,0.15,0.2,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.6e-06,-0.0014,0.0011,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,1.9e-05,2e-05,4.4e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,9.1e-11,2.1e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -37090000,-0.68,0.0023,-0.0039,0.73,0.15,0.21,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.5e-06,-0.0014,0.0011,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.9e-05,2e-05,4.3e-05,0.056,0.057,0.0057,0.55,0.55,0.031,2.8e-11,2.8e-11,9.1e-11,2.1e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -37190000,-0.68,0.0027,-0.0038,0.73,0.12,0.18,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.5e-06,-0.0016,0.0011,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.8e-05,1.9e-05,4.2e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,9.1e-11,2e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0 -37290000,-0.68,0.0027,-0.0039,0.74,0.12,0.18,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.4e-06,-0.0016,0.0012,-0.00093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.8e-05,1.9e-05,4.1e-05,0.055,0.056,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,9.1e-11,2e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0 -37390000,-0.68,0.0029,-0.0037,0.74,0.099,0.16,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.4e-06,-0.0017,0.0012,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.8e-05,1.9e-05,4e-05,0.049,0.05,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,9.1e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 -37490000,-0.68,0.0029,-0.0037,0.74,0.098,0.16,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.3e-06,-0.0017,0.0012,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.8e-05,1.9e-05,3.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,9.1e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0 -37590000,-0.68,0.003,-0.0036,0.74,0.078,0.14,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.3e-06,-0.0018,0.0013,-0.00094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.7e-05,1.8e-05,3.8e-05,0.048,0.049,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,9.1e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0 -37690000,-0.68,0.003,-0.0036,0.74,0.075,0.14,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.3e-06,-0.0018,0.0013,-0.00095,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,1.7e-05,1.8e-05,3.7e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,9.1e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0 -37790000,-0.68,0.0031,-0.0036,0.74,0.058,0.12,-0.1,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.2e-06,-0.0019,0.0013,-0.00095,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,1.7e-05,1.8e-05,3.6e-05,0.047,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,9.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 -37890000,-0.68,0.0031,-0.0036,0.74,0.055,0.13,-0.095,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.2e-06,-0.0019,0.0013,-0.00095,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.5e-05,0.051,0.052,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,9.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 -37990000,-0.68,0.0032,-0.0036,0.74,0.04,0.11,-0.086,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,-2.1e-06,-0.0019,0.0014,-0.00096,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.4e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,9.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 -38090000,-0.68,0.0031,-0.0036,0.74,0.035,0.11,-0.076,-17,-8.2,-3.7e+02,-1.7e-05,-5.8e-05,-2.1e-06,-0.0019,0.0014,-0.00096,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.4e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,2.9e-11,9.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0 -38190000,-0.68,0.0032,-0.0036,0.74,0.022,0.096,-0.068,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-2e-06,-0.002,0.0014,-0.00097,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,9.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 -38290000,-0.68,0.0032,-0.0036,0.74,0.018,0.098,-0.061,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-2e-06,-0.002,0.0014,-0.00097,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.2e-05,0.049,0.049,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,9.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0 -38390000,-0.68,0.0032,-0.0035,0.74,0.0092,0.084,-0.053,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-1.9e-06,-0.0021,0.0014,-0.00098,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.2e-05,0.044,0.044,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,9.2e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38490000,-0.68,0.0032,-0.0035,0.74,0.005,0.087,-0.046,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-1.9e-06,-0.0021,0.0014,-0.00098,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3.1e-05,0.047,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,9.2e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38590000,-0.68,0.0032,-0.0034,0.74,0.00024,0.074,-0.039,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-1.8e-06,-0.0021,0.0014,-0.00098,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3e-05,0.043,0.043,0.0071,0.62,0.62,0.031,3e-11,3e-11,9.2e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38690000,-0.68,0.0031,-0.0034,0.74,-0.0051,0.074,-0.032,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-1.8e-06,-0.0021,0.0014,-0.00099,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,9.2e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0 -38790000,-0.68,0.0031,-0.0034,0.74,-0.01,0.062,-0.024,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-1.7e-06,-0.0022,0.0014,-0.00099,0.37,0.0037,0.025,0,0,0,0,0,4e-05,1.7e-05,1.8e-05,2.9e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,9.2e-11,1.4e-06,1.3e-06,5e-08,0,0,0,0,0,0,0,0 -38890000,-0.68,0.0029,-0.0035,0.74,-0.021,0.052,0.48,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,-1.7e-06,-0.0022,0.0014,-0.00099,0.37,0.0037,0.025,0,0,0,0,0,4e-05,1.7e-05,1.8e-05,2.9e-05,0.044,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,9.2e-11,1.4e-06,1.3e-06,5e-08,0,0,0,0,0,0,0,0 +10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,4.9e-07,0.0025,0.0025,0.005,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +90000,1,-0.0096,-0.01,-0.02,-0.0004,0.0026,-0.026,-1.4e-05,0.00011,-0.0023,0,0,0,0,0,0,0.19,-9.3e-10,0.4,0,0,0,0,0,5.2e-07,0.0026,0.0026,0.0051,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +190000,1,-0.0096,-0.011,-0.02,0.0002,0.0039,-0.041,6e-06,0.00043,-0.0044,-3e-11,-2.3e-12,4.9e-13,0,0,-2e-09,0.19,-9.3e-10,0.4,0,0,0,0,0,5.8e-07,0.0027,0.0027,0.0052,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +290000,1,-0.0097,-0.011,-0.02,0.0012,0.0063,-0.053,5e-05,0.00036,-0.007,9.1e-10,9.1e-11,-2.1e-11,0,0,-4.8e-07,0.19,-9.3e-10,0.4,0,0,0,0,0,6.8e-07,0.0029,0.0029,0.0054,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +390000,1,-0.0089,-0.012,0.046,0.0026,0.0083,-0.059,0.00024,0.0011,-0.0094,-1.1e-08,2.8e-09,2.7e-10,0,0,-4.5e-06,0.17,0.0017,0.41,0,0,0,0,0,7e-07,0.0031,0.0031,0.0056,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +490000,0.87,-0.0023,-0.015,0.5,0.0023,0.0057,-0.06,0.0002,0.00051,-0.011,1.6e-06,-3.8e-07,-4.1e-08,0,0,-1.6e-05,0.14,0.0014,0.42,0,0,0,0,0,2.9e-06,0.0033,0.0033,0.0058,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +590000,0.76,0.00067,-0.015,0.65,0.00071,0.0084,-0.059,0.00037,0.0012,-0.012,1.6e-06,-3.5e-07,-3.8e-08,0,0,-3.4e-05,0.18,0.0018,0.43,0,0,0,0,0,1.9e-05,0.0036,0.0036,0.0061,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +690000,0.72,0.0016,-0.016,0.69,-0.00082,0.0075,-0.06,7.2e-05,0.00069,-0.013,5.4e-06,-2.4e-06,-1.7e-07,0,0,-6.3e-05,0.2,0.002,0.43,0,0,0,0,0,5.9e-05,0.0039,0.0039,0.0064,2.6,2.6,2.8,0.26,0.26,0.29,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +790000,0.71,0.002,-0.016,0.7,-0.0028,0.0098,-0.063,-9.3e-05,0.0015,-0.014,5.3e-06,-2.3e-06,-1.6e-07,0,0,-9.5e-05,0.2,0.002,0.43,0,0,0,0,0,0.00012,0.0042,0.0042,0.0066,2.7,2.7,2,0.42,0.42,0.28,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +890000,0.71,0.0021,-0.016,0.7,-0.0034,0.011,-0.077,-0.00019,0.0011,-0.021,1.7e-05,-9e-06,-6.6e-07,0,0,-9.5e-05,0.2,0.002,0.43,0,0,0,0,0,0.00021,0.0046,0.0046,0.0069,1.3,1.3,2,0.2,0.2,0.43,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +990000,0.7,0.0025,-0.016,0.71,-0.0038,0.015,-0.092,-0.00057,0.0024,-0.029,1.7e-05,-9e-06,-6.6e-07,0,0,-9.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00033,0.005,0.005,0.0073,1.4,1.4,2,0.3,0.3,0.61,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1090000,0.7,0.0025,-0.017,0.71,-0.0034,0.016,-0.11,-0.00043,0.0019,-0.039,5.5e-05,-3.7e-05,-2.5e-06,0,0,-9.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00047,0.0053,0.0053,0.0076,0.89,0.89,2,0.17,0.17,0.84,0.0099,0.0099,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1190000,0.7,0.0027,-0.017,0.71,-0.0037,0.02,-0.12,-0.00079,0.0037,-0.051,5.5e-05,-3.7e-05,-2.5e-06,0,0,-9.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00064,0.0058,0.0058,0.008,1.1,1.1,2,0.24,0.24,1.1,0.0099,0.0099,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1290000,0.7,0.0028,-0.017,0.71,-0.0034,0.02,-0.14,-0.00055,0.0028,-0.064,0.00014,-0.00013,-7.3e-06,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00083,0.006,0.006,0.0084,0.84,0.84,2,0.15,0.15,1.4,0.0096,0.0096,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1390000,0.7,0.0029,-0.017,0.71,-0.0032,0.026,-0.15,-0.0009,0.0052,-0.078,0.00014,-0.00013,-7.3e-06,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.001,0.0066,0.0066,0.0088,1.1,1.1,2,0.21,0.21,1.7,0.0096,0.0096,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1490000,0.7,0.0027,-0.017,0.71,-0.0024,0.025,-0.16,-0.0006,0.0039,-0.093,0.00029,-0.00034,-1.7e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.0013,0.0063,0.0063,0.0093,0.9,0.9,2,0.14,0.14,2.1,0.009,0.009,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1590000,0.7,0.0029,-0.018,0.71,-0.0029,0.031,-0.18,-0.00087,0.0066,-0.11,0.00029,-0.00034,-1.7e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.0016,0.0069,0.0069,0.0097,1.2,1.2,2,0.2,0.2,2.6,0.009,0.009,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1690000,0.7,0.0025,-0.018,0.71,0.00055,0.028,-0.19,-0.00048,0.0047,-0.13,0.0005,-0.0007,-3.1e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.0018,0.0061,0.006,0.01,0.97,0.97,2,0.13,0.13,3,0.0081,0.0081,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1790000,0.7,0.0027,-0.018,0.71,0.0025,0.036,-0.2,-0.00035,0.0078,-0.15,0.0005,-0.0007,-3.1e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.0022,0.0066,0.0066,0.011,1.3,1.3,2,0.2,0.2,3.5,0.0081,0.0081,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1890000,0.7,0.003,-0.018,0.72,0.0038,0.044,-0.22,-2.9e-05,0.012,-0.17,0.0005,-0.0007,-3.1e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.0025,0.0073,0.0073,0.011,1.6,1.6,2,0.3,0.3,4.1,0.0081,0.0081,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1990000,0.7,0.0025,-0.018,0.72,0.0056,0.037,-0.23,0.00047,0.0085,-0.19,0.00068,-0.0012,-4.8e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0029,0.0059,0.0059,0.012,1.3,1.3,2,0.2,0.2,4.7,0.007,0.007,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2090000,0.7,0.0026,-0.018,0.72,0.0083,0.043,-0.24,0.0012,0.012,-0.22,0.00068,-0.0012,-4.8e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0033,0.0064,0.0064,0.012,1.6,1.6,2.1,0.3,0.3,5.3,0.007,0.007,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2190000,0.7,0.0021,-0.018,0.72,0.0084,0.034,-0.26,0.0012,0.0083,-0.24,0.0008,-0.0018,-6.3e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0037,0.0049,0.0049,0.013,1.2,1.2,2.1,0.19,0.19,6,0.0058,0.0058,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2290000,0.7,0.0021,-0.018,0.72,0.011,0.041,-0.27,0.0022,0.012,-0.27,0.0008,-0.0018,-6.3e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0041,0.0054,0.0054,0.014,1.5,1.5,2.1,0.29,0.29,6.7,0.0058,0.0058,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2390000,0.7,0.0016,-0.017,0.72,0.011,0.031,-0.29,0.0019,0.0078,-0.3,0.00083,-0.0024,-7.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0046,0.004,0.004,0.014,1,1,2.1,0.19,0.19,7.4,0.0049,0.0049,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2490000,0.7,0.0017,-0.018,0.72,0.014,0.036,-0.3,0.0031,0.011,-0.32,0.00083,-0.0024,-7.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0051,0.0044,0.0044,0.015,1.3,1.3,2.1,0.27,0.27,8.2,0.0049,0.0049,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2590000,0.7,0.0014,-0.017,0.72,0.012,0.027,-0.31,0.0023,0.0071,-0.36,0.0008,-0.0028,-8.4e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0056,0.0033,0.0033,0.016,0.89,0.89,2.1,0.18,0.18,9.1,0.0041,0.0041,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2690000,0.7,0.0014,-0.017,0.72,0.015,0.031,-0.33,0.0037,0.01,-0.39,0.0008,-0.0028,-8.4e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0062,0.0036,0.0036,0.016,1.1,1.1,2.2,0.25,0.25,10,0.0041,0.0041,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2790000,0.7,0.0012,-0.017,0.72,0.014,0.024,-0.34,0.0027,0.0064,-0.42,0.00071,-0.0033,-9e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0068,0.0028,0.0028,0.017,0.77,0.77,2.2,0.16,0.16,11,0.0034,0.0034,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2890000,0.7,0.0012,-0.017,0.72,0.016,0.027,-0.35,0.0041,0.0089,-0.46,0.00071,-0.0033,-9e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0074,0.0031,0.003,0.018,0.96,0.96,2.2,0.23,0.23,12,0.0034,0.0034,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2990000,0.7,0.0011,-0.017,0.72,0.014,0.022,-0.36,0.003,0.0058,-0.49,0.0006,-0.0036,-9.4e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.008,0.0024,0.0024,0.019,0.68,0.68,2.2,0.15,0.15,13,0.0029,0.0029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3090000,0.7,0.0011,-0.017,0.72,0.017,0.024,-0.38,0.0045,0.0081,-0.53,0.0006,-0.0036,-9.4e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0087,0.0026,0.0026,0.02,0.84,0.84,2.2,0.22,0.22,14,0.0029,0.0029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3190000,0.7,0.0009,-0.017,0.72,0.014,0.019,-0.39,0.0032,0.0053,-0.57,0.00046,-0.0039,-9.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0093,0.0021,0.0021,0.021,0.6,0.6,2.3,0.14,0.14,15,0.0025,0.0025,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3290000,0.7,0.00089,-0.017,0.72,0.017,0.023,-0.4,0.0047,0.0074,-0.61,0.00046,-0.0039,-9.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.01,0.0023,0.0023,0.021,0.74,0.74,2.3,0.2,0.2,16,0.0025,0.0025,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3390000,0.7,0.00085,-0.017,0.72,0.015,0.018,-0.42,0.0033,0.0049,-0.65,0.00031,-0.0042,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.011,0.0018,0.0018,0.022,0.54,0.54,2.3,0.14,0.14,17,0.0021,0.0021,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3490000,0.7,0.00086,-0.017,0.72,0.019,0.021,-0.43,0.005,0.0068,-0.69,0.00031,-0.0042,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.012,0.002,0.002,0.023,0.67,0.67,2.3,0.19,0.19,19,0.0021,0.0021,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3590000,0.7,0.00079,-0.017,0.72,0.017,0.016,-0.44,0.0036,0.0045,-0.73,0.00015,-0.0044,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.012,0.0016,0.0016,0.024,0.5,0.5,2.4,0.13,0.13,20,0.0018,0.0018,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3690000,0.7,0.00079,-0.017,0.72,0.021,0.018,-0.46,0.0055,0.0063,-0.78,0.00015,-0.0044,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.013,0.0018,0.0018,0.025,0.61,0.61,2.4,0.18,0.18,21,0.0018,0.0018,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3790000,0.7,0.00073,-0.017,0.72,0.02,0.014,-0.47,0.004,0.0042,-0.83,-3.1e-05,-0.0046,-9.5e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.014,0.0015,0.0014,0.026,0.46,0.46,2.4,0.12,0.12,23,0.0015,0.0015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3890000,0.7,0.00077,-0.017,0.72,0.022,0.016,-0.48,0.0061,0.0057,-0.87,-3.1e-05,-0.0046,-9.5e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.015,0.0016,0.0016,0.027,0.56,0.56,2.4,0.17,0.17,24,0.0015,0.0015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3990000,0.7,0.00081,-0.017,0.72,0.025,0.019,-0.5,0.0084,0.0074,-0.92,-3.1e-05,-0.0046,-9.5e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.016,0.0018,0.0017,0.028,0.68,0.68,2.5,0.23,0.23,26,0.0015,0.0015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4090000,0.7,0.00079,-0.016,0.72,0.021,0.016,-0.51,0.0062,0.0053,-0.97,-0.00022,-0.0048,-9.3e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.017,0.0014,0.0014,0.029,0.52,0.52,2.5,0.16,0.16,27,0.0012,0.0012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4190000,0.7,0.00077,-0.016,0.72,0.025,0.018,-0.53,0.0086,0.007,-1,-0.00022,-0.0048,-9.3e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.018,0.0016,0.0015,0.03,0.63,0.63,2.5,0.22,0.22,29,0.0012,0.0012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4290000,0.7,0.0008,-0.016,0.72,0.019,0.015,-0.54,0.0063,0.005,-1.1,-0.00041,-0.005,-9e-05,0,0,-9.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.018,0.0013,0.0012,0.032,0.48,0.48,2.6,0.15,0.15,31,0.001,0.001,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4390000,0.7,0.00068,-0.016,0.71,0.021,0.016,-0.55,0.0083,0.0066,-1.1,-0.00041,-0.005,-9e-05,0,0,-9.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.019,0.0014,0.0014,0.033,0.58,0.58,2.6,0.2,0.2,33,0.001,0.001,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4490000,0.7,0.00073,-0.016,0.71,0.017,0.013,-0.57,0.0058,0.0046,-1.2,-0.00059,-0.0051,-8.8e-05,0,0,-8.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.02,0.0011,0.0011,0.034,0.44,0.44,2.6,0.14,0.14,34,0.00083,0.00083,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4590000,0.7,0.00069,-0.016,0.71,0.019,0.015,-0.58,0.0076,0.006,-1.2,-0.00059,-0.0051,-8.8e-05,0,0,-8.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.022,0.0012,0.0012,0.035,0.53,0.53,2.7,0.19,0.19,36,0.00083,0.00083,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4690000,0.7,0.0007,-0.016,0.71,0.016,0.012,-0.6,0.0054,0.0043,-1.3,-0.00074,-0.0052,-8.6e-05,0,0,-8.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.023,0.00097,0.00095,0.036,0.41,0.41,2.7,0.14,0.14,38,0.00068,0.00068,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4790000,0.7,0.00063,-0.016,0.71,0.018,0.014,-0.61,0.0071,0.0056,-1.4,-0.00074,-0.0052,-8.6e-05,0,0,-8.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.024,0.0011,0.001,0.038,0.49,0.49,2.7,0.18,0.18,40,0.00068,0.00068,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4890000,0.7,0.00065,-0.016,0.71,0.016,0.011,-0.63,0.0051,0.0039,-1.4,-0.00088,-0.0053,-8.4e-05,0,0,-7.9e-05,0.21,0.0021,0.43,0,0,0,0,0,0.025,0.00085,0.00083,0.039,0.37,0.37,2.8,0.13,0.13,42,0.00055,0.00055,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4990000,0.7,0.00068,-0.016,0.71,0.017,0.013,-0.64,0.0068,0.0051,-1.5,-0.00088,-0.0053,-8.4e-05,0,0,-7.9e-05,0.21,0.0021,0.43,0,0,0,0,0,0.026,0.00092,0.00089,0.04,0.44,0.44,2.8,0.17,0.17,44,0.00055,0.00055,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5090000,0.7,0.00069,-0.015,0.71,0.014,0.01,-0.66,0.0049,0.0036,-1.6,-0.001,-0.0054,-8.3e-05,0,0,-7.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.027,0.00074,0.00071,0.042,0.34,0.34,2.8,0.13,0.13,46,0.00044,0.00044,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5190000,0.7,0.00068,-0.015,0.71,0.016,0.011,-0.67,0.0064,0.0047,-1.6,-0.001,-0.0054,-8.3e-05,0,0,-7.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.028,0.00079,0.00077,0.043,0.4,0.4,2.9,0.16,0.16,49,0.00044,0.00044,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5290000,0.7,0.00075,-0.015,0.71,0.012,0.0072,-0.68,0.0046,0.0033,-1.7,-0.0011,-0.0055,-8.2e-05,0,0,-7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.029,0.00064,0.00062,0.044,0.31,0.31,2.9,0.12,0.12,51,0.00036,0.00036,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5390000,0.7,0.00084,-0.015,0.71,0.014,0.0066,-0.7,0.0058,0.0039,-1.8,-0.0011,-0.0055,-8.2e-05,0,0,-7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.031,0.00068,0.00066,0.046,0.37,0.37,2.9,0.16,0.16,53,0.00036,0.00036,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5490000,0.7,0.00091,-0.015,0.71,0.011,0.0042,-0.71,0.0042,0.0026,-1.8,-0.0012,-0.0055,-8.1e-05,0,0,-6.7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.032,0.00055,0.00053,0.047,0.28,0.28,3,0.11,0.11,56,0.00029,0.00029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5590000,0.7,0.00092,-0.015,0.71,0.012,0.0047,-0.73,0.0053,0.003,-1.9,-0.0012,-0.0055,-8.1e-05,0,0,-6.7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.033,0.00059,0.00057,0.049,0.33,0.33,3,0.15,0.15,58,0.00029,0.00029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5690000,0.7,0.001,-0.015,0.71,0.0081,0.003,-0.74,0.0037,0.002,-2,-0.0013,-0.0056,-8e-05,0,0,-6.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.035,0.00048,0.00046,0.05,0.26,0.26,3.1,0.11,0.11,61,0.00023,0.00023,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5790000,0.7,0.0011,-0.015,0.71,0.0074,0.0032,-0.75,0.0045,0.0023,-2.1,-0.0013,-0.0056,-8e-05,0,0,-6.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.036,0.00051,0.00049,0.052,0.3,0.3,3.1,0.14,0.14,64,0.00023,0.00023,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5890000,0.7,0.0011,-0.015,0.71,0.0048,0.0028,0.0028,0.003,0.0016,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-6.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.037,0.00042,0.00039,0.053,0.23,0.23,9.8,0.11,0.11,0.52,0.00019,0.00019,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5990000,0.7,0.0011,-0.015,0.71,0.0037,0.0029,0.015,0.0034,0.0018,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-7.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.039,0.00044,0.00042,0.055,0.27,0.27,8.8,0.13,0.13,0.33,0.00019,0.00019,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6090000,0.7,0.0011,-0.015,0.71,0.0029,0.0038,-0.011,0.0037,0.0022,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-6.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.04,0.00047,0.00045,0.056,0.32,0.32,7,0.17,0.17,0.33,0.00019,0.00019,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6190000,0.7,0.0011,-0.015,0.71,-0.00035,0.0027,-0.005,0.0022,0.0015,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-8.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.041,0.00039,0.00036,0.058,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6290000,0.7,0.0011,-0.015,0.71,-6.8e-05,0.0039,-0.012,0.0022,0.0019,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.043,0.00041,0.00038,0.059,0.29,0.29,3.2,0.16,0.16,0.3,0.00015,0.00015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6390000,0.7,0.0012,-0.014,0.71,-0.0018,0.0033,-0.05,0.0012,0.0014,-3.7e+02,-0.0014,-0.0056,-8e-05,0,0,-3.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.044,0.00034,0.00031,0.061,0.23,0.23,2.3,0.12,0.12,0.29,0.00013,0.00012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6490000,0.7,0.0012,-0.015,0.71,-0.0017,0.0039,-0.052,0.001,0.0018,-3.7e+02,-0.0014,-0.0056,-8e-05,0,0,-8.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.046,0.00036,0.00033,0.063,0.26,0.26,1.5,0.15,0.15,0.26,0.00013,0.00012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6590000,0.71,0.0012,-0.015,0.71,-0.0024,0.0029,-0.099,0.00044,0.0014,-3.7e+02,-0.0014,-0.0057,4e-05,0,0,9.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0049,0.00026,0.00026,0.0018,0.19,0.19,1.1,0.12,0.12,0.23,0.0001,0.0001,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6690000,0.7,0.0012,-0.015,0.71,-0.0016,0.0037,-0.076,0.00024,0.0017,-3.7e+02,-0.0014,-0.0056,-0.00051,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0042,0.00026,0.00026,0.0008,0.19,0.19,0.78,0.14,0.14,0.21,0.0001,0.0001,0.0099,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6790000,0.71,0.0012,-0.014,0.71,-0.0026,0.0034,-0.11,3.7e-05,0.0021,-3.7e+02,-0.0014,-0.0057,-0.00012,0,0,1e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0041,0.00026,0.00026,0.00055,0.2,0.2,0.6,0.17,0.17,0.2,0.0001,0.0001,0.0098,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6890000,0.71,0.0012,-0.014,0.71,-0.0042,0.0037,-0.12,-0.00032,0.0025,-3.7e+02,-0.0014,-0.0057,0.00023,0,0,-4.1e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00026,0.00026,0.00042,0.21,0.21,0.46,0.21,0.21,0.18,0.0001,0.0001,0.0096,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6990000,0.7,0.0013,-0.014,0.71,-0.0039,0.0042,-0.12,-0.00073,0.0028,-3.7e+02,-0.0014,-0.0056,-0.0017,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00026,0.00026,0.00036,0.22,0.22,0.36,0.25,0.25,0.16,0.0001,0.0001,0.0093,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7090000,0.7,0.0013,-0.014,0.71,-0.004,0.0034,-0.13,-0.0011,0.003,-3.7e+02,-0.0015,-0.0056,-0.0039,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00034,0.23,0.23,0.29,0.29,0.29,0.16,0.0001,0.0001,0.0088,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7190000,0.7,0.0013,-0.014,0.71,-0.0053,0.0033,-0.15,-0.0016,0.0033,-3.7e+02,-0.0015,-0.0056,-0.0043,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00033,0.25,0.25,0.24,0.34,0.34,0.15,0.0001,0.0001,0.0082,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7290000,0.7,0.0013,-0.014,0.71,-0.0064,0.0034,-0.15,-0.0022,0.0037,-3.7e+02,-0.0014,-0.0056,-0.0035,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00032,0.27,0.27,0.2,0.4,0.4,0.14,0.0001,0.0001,0.0075,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7390000,0.7,0.0013,-0.014,0.71,-0.006,0.0047,-0.16,-0.0028,0.0042,-3.7e+02,-0.0014,-0.0056,-0.0027,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00028,0.00028,0.00033,0.29,0.29,0.18,0.46,0.46,0.13,0.0001,0.0001,0.0068,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7490000,0.7,0.0014,-0.014,0.71,-0.0072,0.0049,-0.16,-0.0035,0.0047,-3.7e+02,-0.0014,-0.0056,-0.0022,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00028,0.00028,0.00032,0.32,0.32,0.15,0.53,0.53,0.12,0.0001,9.9e-05,0.006,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7590000,0.7,0.0014,-0.014,0.71,-0.0086,0.0061,-0.17,-0.0042,0.0054,-3.7e+02,-0.0014,-0.0057,-0.00052,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00029,0.00028,0.00032,0.35,0.35,0.14,0.6,0.6,0.12,0.0001,9.9e-05,0.0053,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7690000,0.7,0.0014,-0.014,0.71,-0.0099,0.0067,-0.16,-0.0051,0.006,-3.7e+02,-0.0014,-0.0057,-0.0005,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00029,0.00029,0.00032,0.38,0.38,0.13,0.69,0.69,0.11,9.9e-05,9.9e-05,0.0047,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7790000,0.7,0.0015,-0.014,0.71,-0.011,0.0072,-0.16,-0.0061,0.0064,-3.7e+02,-0.0014,-0.0056,-0.0025,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.0003,0.0003,0.00031,0.41,0.41,0.12,0.78,0.78,0.11,9.8e-05,9.8e-05,0.004,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7890000,0.7,0.0015,-0.014,0.71,-0.013,0.0089,-0.16,-0.0073,0.0073,-3.7e+02,-0.0014,-0.0056,-0.0013,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.0003,0.0003,0.00031,0.45,0.45,0.11,0.89,0.89,0.1,9.8e-05,9.8e-05,0.0035,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +7990000,0.7,0.0015,-0.014,0.71,-0.014,0.0099,-0.16,-0.0086,0.0083,-3.7e+02,-0.0014,-0.0057,-0.00039,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00031,0.00031,0.0003,0.49,0.49,0.1,1,1,0.099,9.7e-05,9.7e-05,0.003,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +8090000,0.7,0.0015,-0.014,0.71,-0.016,0.011,-0.17,-0.01,0.0095,-3.7e+02,-0.0014,-0.0057,0.00082,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00032,0.00031,0.00029,0.53,0.53,0.1,1.1,1.1,0.097,9.7e-05,9.7e-05,0.0026,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8190000,0.7,0.0015,-0.014,0.71,-0.018,0.012,-0.18,-0.012,0.01,-3.7e+02,-0.0014,-0.0057,-0.00029,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00032,0.00032,0.00028,0.58,0.58,0.099,1.3,1.3,0.094,9.7e-05,9.7e-05,0.0023,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8290000,0.7,0.0015,-0.014,0.71,-0.019,0.013,-0.17,-0.014,0.011,-3.7e+02,-0.0014,-0.0056,-0.00084,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00033,0.00033,0.00027,0.63,0.63,0.097,1.4,1.4,0.091,9.6e-05,9.6e-05,0.002,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +8390000,0.7,0.0016,-0.014,0.71,-0.02,0.014,-0.17,-0.016,0.013,-3.7e+02,-0.0014,-0.0057,0.00015,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00034,0.00034,0.00027,0.68,0.68,0.097,1.6,1.6,0.091,9.6e-05,9.6e-05,0.0018,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +8490000,0.7,0.0015,-0.014,0.71,-0.021,0.015,-0.17,-0.017,0.014,-3.7e+02,-0.0014,-0.0057,-0.00022,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00034,0.00034,0.00026,0.73,0.73,0.096,1.8,1.8,0.089,9.5e-05,9.5e-05,0.0015,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8590000,0.7,0.0016,-0.014,0.71,-0.023,0.017,-0.17,-0.02,0.015,-3.7e+02,-0.0014,-0.0056,-0.00092,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00035,0.00035,0.00025,0.79,0.79,0.095,2,2,0.088,9.5e-05,9.5e-05,0.0013,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8690000,0.7,0.0016,-0.014,0.71,-0.026,0.018,-0.16,-0.022,0.017,-3.7e+02,-0.0014,-0.0057,9e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00036,0.00036,0.00024,0.84,0.84,0.096,2.2,2.2,0.088,9.4e-05,9.4e-05,0.0012,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +8790000,0.7,0.0016,-0.014,0.71,-0.027,0.019,-0.15,-0.025,0.018,-3.7e+02,-0.0014,-0.0057,-0.00031,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00037,0.00037,0.00023,0.91,0.91,0.095,2.5,2.5,0.087,9.4e-05,9.4e-05,0.0011,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +8890000,0.7,0.0016,-0.014,0.71,-0.029,0.02,-0.15,-0.027,0.02,-3.7e+02,-0.0014,-0.0057,-0.00051,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00037,0.00037,0.00022,0.96,0.96,0.095,2.7,2.7,0.086,9.2e-05,9.2e-05,0.00094,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +8990000,0.7,0.0016,-0.014,0.71,-0.03,0.02,-0.14,-0.03,0.021,-3.7e+02,-0.0014,-0.0056,-0.001,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00038,0.00038,0.00022,1,1,0.096,3,3,0.087,9.2e-05,9.2e-05,0.00085,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +9090000,0.7,0.0017,-0.014,0.71,-0.032,0.02,-0.14,-0.033,0.022,-3.7e+02,-0.0014,-0.0056,-0.0012,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00038,0.00038,0.00021,1.1,1.1,0.095,3.3,3.3,0.086,9.1e-05,9.1e-05,0.00076,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +9190000,0.7,0.0017,-0.014,0.71,-0.033,0.021,-0.14,-0.036,0.025,-3.7e+02,-0.0014,-0.0057,-9.6e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00039,0.00039,0.0002,1.2,1.2,0.094,3.6,3.6,0.085,9.1e-05,9.1e-05,0.00068,0.04,0.04,0.027,0,0,0,0,0,0,0,0 +9290000,0.7,0.0016,-0.014,0.71,-0.033,0.022,-0.14,-0.038,0.026,-3.7e+02,-0.0014,-0.0057,1.3e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00039,0.00039,0.0002,1.2,1.2,0.093,3.9,3.9,0.085,8.9e-05,8.9e-05,0.00061,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +9390000,0.7,0.0016,-0.014,0.71,-0.034,0.024,-0.14,-0.042,0.028,-3.7e+02,-0.0014,-0.0057,2.6e-07,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.0004,0.00019,1.3,1.3,0.093,4.3,4.3,0.086,8.9e-05,8.9e-05,0.00056,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +9490000,0.7,0.0016,-0.014,0.71,-0.034,0.023,-0.13,-0.044,0.029,-3.7e+02,-0.0013,-0.0057,0.00059,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.0004,0.0004,0.00019,1.3,1.3,0.091,4.6,4.6,0.085,8.7e-05,8.7e-05,0.0005,0.04,0.04,0.023,0,0,0,0,0,0,0,0 +9590000,0.7,0.0016,-0.014,0.71,-0.036,0.024,-0.13,-0.047,0.031,-3.7e+02,-0.0013,-0.0057,0.00069,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00018,1.4,1.4,0.09,5.1,5.1,0.085,8.7e-05,8.7e-05,0.00046,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +9690000,0.7,0.0017,-0.014,0.71,-0.037,0.025,-0.12,-0.049,0.031,-3.7e+02,-0.0013,-0.0057,0.00013,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00018,1.4,1.4,0.089,5.3,5.3,0.086,8.5e-05,8.5e-05,0.00042,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +9790000,0.7,0.0016,-0.014,0.71,-0.036,0.027,-0.11,-0.053,0.034,-3.7e+02,-0.0013,-0.0057,0.00044,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00017,1.5,1.5,0.087,5.9,5.9,0.085,8.5e-05,8.5e-05,0.00038,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +9890000,0.7,0.0016,-0.014,0.71,-0.036,0.027,-0.11,-0.053,0.034,-3.7e+02,-0.0013,-0.0057,0.00037,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00017,1.5,1.5,0.084,6.1,6.1,0.085,8.2e-05,8.2e-05,0.00035,0.04,0.04,0.018,0,0,0,0,0,0,0,0 +9990000,0.7,0.0017,-0.014,0.71,-0.038,0.027,-0.1,-0.057,0.037,-3.7e+02,-0.0013,-0.0057,0.00015,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00016,1.6,1.6,0.083,6.7,6.7,0.086,8.2e-05,8.2e-05,0.00033,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +10090000,0.7,0.0017,-0.014,0.71,-0.036,0.026,-0.096,-0.057,0.036,-3.7e+02,-0.0013,-0.0057,0.00023,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00016,1.6,1.6,0.08,6.9,6.9,0.085,8e-05,8e-05,0.0003,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +10190000,0.7,0.0017,-0.014,0.71,-0.037,0.028,-0.096,-0.061,0.039,-3.7e+02,-0.0013,-0.0057,-0.00029,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00015,1.7,1.7,0.078,7.6,7.6,0.084,8e-05,8e-05,0.00027,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10290000,0.7,0.0017,-0.014,0.71,-0.038,0.028,-0.084,-0.065,0.041,-3.7e+02,-0.0013,-0.0057,-0.00057,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00043,0.00043,0.00015,1.8,1.8,0.076,8.3,8.3,0.085,8e-05,8e-05,0.00026,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10390000,0.7,0.0016,-0.014,0.71,0.01,-0.02,0.0096,0.0009,-0.0018,-3.7e+02,-0.0013,-0.0057,-0.00051,-6.4e-08,5.1e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00045,0.00045,0.00015,0.25,0.25,0.56,0.25,0.25,0.078,8e-05,8e-05,0.00024,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +10490000,0.7,0.0017,-0.014,0.71,0.0097,-0.018,0.023,0.0019,-0.0036,-3.7e+02,-0.0013,-0.0057,-0.00073,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00046,0.00046,0.00014,0.26,0.26,0.55,0.26,0.26,0.08,8e-05,8e-05,0.00022,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10590000,0.7,0.0017,-0.014,0.71,0.0092,-0.0076,0.026,0.0018,-0.00084,-3.7e+02,-0.0013,-0.0057,-0.00066,-0.00028,7.5e-06,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00047,0.00047,0.00014,0.13,0.13,0.27,0.13,0.13,0.073,7.9e-05,7.9e-05,0.0002,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10690000,0.7,0.0018,-0.014,0.71,0.0079,-0.0075,0.03,0.0027,-0.0016,-3.7e+02,-0.0013,-0.0057,-0.0007,-0.00028,8.7e-06,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00048,0.00014,0.14,0.14,0.26,0.14,0.14,0.078,7.9e-05,7.9e-05,0.00019,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10790000,0.7,0.0018,-0.014,0.71,0.0072,-0.0048,0.024,0.0028,-0.0008,-3.7e+02,-0.0013,-0.0056,-0.00062,-0.0005,7.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00047,0.00013,0.099,0.099,0.17,0.091,0.091,0.072,7.8e-05,7.8e-05,0.00018,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10890000,0.7,0.0017,-0.014,0.71,0.0067,-0.0041,0.02,0.0034,-0.0012,-3.7e+02,-0.0013,-0.0056,-0.00059,-0.0005,7e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00049,0.00049,0.00013,0.11,0.11,0.16,0.098,0.098,0.075,7.8e-05,7.8e-05,0.00016,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10990000,0.7,0.0017,-0.014,0.71,0.0086,0.00072,0.014,0.0048,-0.0024,-3.7e+02,-0.0013,-0.0056,-0.00034,-0.001,0.00061,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00047,0.00047,0.00013,0.09,0.09,0.12,0.073,0.073,0.071,7.5e-05,7.5e-05,0.00015,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11090000,0.7,0.0017,-0.014,0.71,0.0079,0.0025,0.019,0.0056,-0.0023,-3.7e+02,-0.0013,-0.0056,-0.00012,-0.001,0.00061,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00048,0.00012,0.11,0.11,0.11,0.079,0.079,0.074,7.5e-05,7.5e-05,0.00014,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11190000,0.7,0.0017,-0.014,0.71,0.012,0.0053,0.0077,0.0067,-0.0031,-3.7e+02,-0.0012,-0.0056,-0.00025,-0.0013,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00044,0.00044,0.00012,0.088,0.088,0.084,0.063,0.063,0.069,7e-05,7e-05,0.00014,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11290000,0.7,0.0018,-0.014,0.71,0.012,0.0071,0.0074,0.0079,-0.0024,-3.7e+02,-0.0012,-0.0056,-0.00048,-0.0013,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00045,0.00045,0.00012,0.11,0.11,0.078,0.07,0.07,0.072,7e-05,7e-05,0.00013,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11390000,0.7,0.0019,-0.014,0.71,0.0072,0.0067,0.0017,0.0057,-0.0022,-3.7e+02,-0.0013,-0.0056,-0.00064,-0.00099,0.00053,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0004,0.0004,0.00012,0.089,0.089,0.063,0.057,0.057,0.068,6.5e-05,6.5e-05,0.00012,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11490000,0.7,0.0019,-0.014,0.71,0.0051,0.009,0.0025,0.0063,-0.0014,-3.7e+02,-0.0013,-0.0056,-0.00095,-0.00099,0.00053,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00041,0.00041,0.00011,0.11,0.11,0.058,0.065,0.065,0.069,6.5e-05,6.5e-05,0.00011,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11590000,0.7,0.0019,-0.014,0.71,0.00041,0.0084,-0.0034,0.0047,-0.0015,-3.7e+02,-0.0013,-0.0056,-0.00098,-0.00058,0.00027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00036,0.00036,0.00011,0.089,0.089,0.049,0.054,0.054,0.066,6e-05,6e-05,0.00011,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11690000,0.7,0.0018,-0.014,0.71,-0.0021,0.011,-0.0079,0.0046,-0.00059,-3.7e+02,-0.0013,-0.0056,-0.001,-0.00057,0.00026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00037,0.00037,0.00011,0.11,0.11,0.046,0.062,0.062,0.066,6e-05,6e-05,0.0001,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11790000,0.7,0.0019,-0.014,0.71,-0.0081,0.011,-0.0098,0.0021,0.00045,-3.7e+02,-0.0014,-0.0056,-0.001,-0.00051,-0.0001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00032,0.00032,0.00011,0.087,0.087,0.039,0.052,0.052,0.063,5.5e-05,5.6e-05,9.5e-05,0.036,0.036,0.01,0,0,0,0,0,0,0,0 +11890000,0.7,0.0019,-0.014,0.71,-0.0093,0.012,-0.011,0.0012,0.0016,-3.7e+02,-0.0014,-0.0056,-0.0011,-0.00052,-9.6e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00033,0.00033,0.00011,0.1,0.1,0.037,0.06,0.06,0.063,5.5e-05,5.6e-05,9e-05,0.036,0.036,0.01,0,0,0,0,0,0,0,0 +11990000,0.7,0.002,-0.014,0.71,-0.011,0.013,-0.016,-6.6e-05,0.0022,-3.7e+02,-0.0014,-0.0056,-0.0011,-0.00039,-0.00014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00029,0.00029,0.00011,0.083,0.083,0.033,0.051,0.051,0.061,5.1e-05,5.1e-05,8.5e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 +12090000,0.7,0.002,-0.014,0.71,-0.013,0.015,-0.022,-0.0013,0.0036,-3.7e+02,-0.0014,-0.0057,-0.0009,-0.00037,-0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00029,0.00029,0.0001,0.099,0.099,0.031,0.059,0.059,0.061,5.1e-05,5.1e-05,8.1e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 +12190000,0.7,0.0017,-0.014,0.71,-0.007,0.012,-0.017,0.0015,0.002,-3.7e+02,-0.0013,-0.0057,-0.00082,2.1e-05,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00026,0.00026,0.0001,0.079,0.079,0.028,0.05,0.05,0.059,4.8e-05,4.8e-05,7.6e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 +12290000,0.7,0.0017,-0.014,0.71,-0.0094,0.014,-0.016,0.00068,0.0033,-3.7e+02,-0.0013,-0.0057,-0.00077,-5.6e-06,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00027,0.00027,0.0001,0.093,0.093,0.028,0.058,0.058,0.059,4.8e-05,4.8e-05,7.3e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 +12390000,0.7,0.0014,-0.014,0.71,-0.0045,0.011,-0.015,0.0029,0.0018,-3.7e+02,-0.0012,-0.0057,-0.00083,0.00029,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00024,0.00024,9.8e-05,0.075,0.075,0.026,0.05,0.05,0.057,4.5e-05,4.5e-05,6.9e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 +12490000,0.7,0.0014,-0.014,0.71,-0.0056,0.013,-0.018,0.0024,0.003,-3.7e+02,-0.0012,-0.0057,-0.00092,0.00028,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00025,0.00025,9.6e-05,0.087,0.087,0.026,0.058,0.058,0.057,4.5e-05,4.5e-05,6.6e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 +12590000,0.7,0.0015,-0.014,0.71,-0.013,0.011,-0.023,-0.0027,0.0016,-3.7e+02,-0.0013,-0.0058,-0.00089,0.00055,0.00061,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00022,0.00022,9.5e-05,0.07,0.07,0.025,0.049,0.049,0.055,4.3e-05,4.3e-05,6.3e-05,0.035,0.035,0.0099,0,0,0,0,0,0,0,0 +12690000,0.7,0.0015,-0.014,0.71,-0.013,0.012,-0.027,-0.0041,0.0028,-3.7e+02,-0.0013,-0.0058,-0.00094,0.00058,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00023,0.00023,9.3e-05,0.081,0.081,0.025,0.058,0.058,0.055,4.3e-05,4.3e-05,6e-05,0.035,0.035,0.0098,0,0,0,0,0,0,0,0 +12790000,0.7,0.0015,-0.014,0.71,-0.019,0.0092,-0.03,-0.0075,0.0015,-3.7e+02,-0.0013,-0.0058,-0.00087,0.00074,0.00042,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00021,0.00021,9.2e-05,0.066,0.066,0.024,0.049,0.049,0.053,4e-05,4e-05,5.7e-05,0.035,0.035,0.0097,0,0,0,0,0,0,0,0 +12890000,0.7,0.0015,-0.014,0.71,-0.02,0.0092,-0.029,-0.0094,0.0024,-3.7e+02,-0.0013,-0.0058,-0.00082,0.00068,0.00047,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00022,0.00022,9.1e-05,0.076,0.076,0.025,0.057,0.057,0.054,4e-05,4e-05,5.4e-05,0.035,0.035,0.0096,0,0,0,0,0,0,0,0 +12990000,0.7,0.0012,-0.014,0.71,-0.0078,0.0067,-0.03,-0.0011,0.0013,-3.7e+02,-0.0012,-0.0058,-0.00068,0.00069,0.00098,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.9e-05,0.062,0.062,0.025,0.049,0.049,0.052,3.8e-05,3.9e-05,5.2e-05,0.035,0.035,0.0094,0,0,0,0,0,0,0,0 +13090000,0.7,0.0012,-0.014,0.71,-0.0084,0.0069,-0.03,-0.0019,0.002,-3.7e+02,-0.0012,-0.0058,-0.00078,0.00066,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00021,0.00021,8.8e-05,0.071,0.071,0.025,0.057,0.057,0.052,3.8e-05,3.9e-05,4.9e-05,0.035,0.035,0.0094,0,0,0,0,0,0,0,0 +13190000,0.7,0.00097,-0.014,0.71,0.00038,0.0064,-0.027,0.0043,0.0013,-3.7e+02,-0.0012,-0.0059,-0.00075,0.00053,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.6e-05,0.058,0.058,0.025,0.049,0.049,0.051,3.7e-05,3.7e-05,4.7e-05,0.035,0.035,0.0091,0,0,0,0,0,0,0,0 +13290000,0.7,0.00097,-0.014,0.71,0.0002,0.0073,-0.024,0.0043,0.002,-3.7e+02,-0.0012,-0.0059,-0.00063,0.0004,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.5e-05,0.067,0.067,0.027,0.057,0.057,0.051,3.7e-05,3.7e-05,4.5e-05,0.035,0.035,0.0091,0,0,0,0,0,0,0,0 +13390000,0.7,0.00082,-0.014,0.71,0.00098,0.0062,-0.02,0.0032,0.0012,-3.7e+02,-0.0011,-0.0059,-0.00053,0.00027,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,8.4e-05,0.055,0.055,0.026,0.048,0.048,0.05,3.5e-05,3.5e-05,4.3e-05,0.035,0.035,0.0088,0,0,0,0,0,0,0,0 +13490000,0.7,0.00085,-0.014,0.71,0.00055,0.0062,-0.019,0.0033,0.0018,-3.7e+02,-0.0011,-0.0059,-0.00045,0.00019,0.0015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.2e-05,0.063,0.063,0.028,0.056,0.056,0.05,3.5e-05,3.5e-05,4.1e-05,0.035,0.035,0.0087,0,0,0,0,0,0,0,0 +13590000,0.7,0.0008,-0.014,0.71,0.00075,0.0064,-0.021,0.0023,0.0012,-3.7e+02,-0.0011,-0.0059,-0.00049,0.00018,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,8.2e-05,0.052,0.052,0.028,0.048,0.048,0.05,3.4e-05,3.4e-05,4e-05,0.035,0.035,0.0084,0,0,0,0,0,0,0,0 +13690000,0.7,0.00077,-0.014,0.71,0.0015,0.0083,-0.025,0.0024,0.0019,-3.7e+02,-0.0011,-0.0059,-0.00038,0.00021,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8e-05,0.059,0.059,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,3.8e-05,0.035,0.035,0.0083,0,0,0,0,0,0,0,0 +13790000,0.7,0.00066,-0.014,0.71,0.002,0.0041,-0.027,0.0034,-0.00048,-3.7e+02,-0.0011,-0.0059,-0.00037,6.1e-05,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.9e-05,0.05,0.05,0.029,0.048,0.048,0.049,3.2e-05,3.2e-05,3.7e-05,0.035,0.035,0.0079,0,0,0,0,0,0,0,0 +13890000,0.7,0.00063,-0.014,0.71,0.0026,0.0041,-0.031,0.0037,-9.1e-05,-3.7e+02,-0.0011,-0.0059,-0.0003,9.1e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.9e-05,0.056,0.056,0.03,0.056,0.056,0.05,3.2e-05,3.2e-05,3.5e-05,0.035,0.035,0.0078,0,0,0,0,0,0,0,0 +13990000,0.7,0.00056,-0.014,0.71,0.0028,0.0016,-0.03,0.0044,-0.0019,-3.7e+02,-0.0011,-0.006,-0.00028,-0.00013,0.0013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.7e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,3.4e-05,0.035,0.035,0.0074,0,0,0,0,0,0,0,0 +14090000,0.7,0.00054,-0.014,0.71,0.0029,0.0018,-0.031,0.0047,-0.0017,-3.7e+02,-0.0011,-0.006,-0.00017,-0.00012,0.0013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.6e-05,0.054,0.054,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,3.2e-05,0.035,0.035,0.0073,0,0,0,0,0,0,0,0 +14190000,0.7,0.00044,-0.014,0.71,0.0062,0.0012,-0.033,0.0067,-0.0015,-3.7e+02,-0.0011,-0.006,-0.00011,-0.00015,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.6e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,3.1e-05,0.035,0.035,0.0069,0,0,0,0,0,0,0,0 +14290000,0.7,0.00045,-0.014,0.71,0.0071,0.002,-0.032,0.0074,-0.0014,-3.7e+02,-0.0011,-0.006,-6.5e-05,-0.00022,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.5e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,3e-05,0.035,0.035,0.0067,0,0,0,0,0,0,0,0 +14390000,0.7,0.00036,-0.014,0.71,0.0088,0.0029,-0.034,0.0087,-0.0012,-3.7e+02,-0.001,-0.006,4.1e-05,-0.00026,0.00092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7.3e-05,0.044,0.044,0.031,0.047,0.047,0.05,2.8e-05,2.8e-05,2.9e-05,0.034,0.034,0.0063,0,0,0,0,0,0,0,0 +14490000,0.7,0.00035,-0.014,0.71,0.0089,0.0042,-0.037,0.0096,-0.00085,-3.7e+02,-0.001,-0.006,7e-05,-0.00021,0.00088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.2e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,2.8e-05,0.034,0.034,0.0062,0,0,0,0,0,0,0,0 +14590000,0.7,0.00034,-0.013,0.71,0.0054,0.0026,-0.037,0.006,-0.0023,-3.7e+02,-0.0011,-0.006,7.2e-05,-0.0005,0.0013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7.2e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,2.7e-05,0.034,0.034,0.0058,0,0,0,0,0,0,0,0 +14690000,0.7,0.0003,-0.013,0.71,0.0069,-0.00029,-0.034,0.0067,-0.0022,-3.7e+02,-0.0011,-0.006,0.00014,-0.0006,0.0014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.1e-05,0.048,0.048,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,2.6e-05,0.034,0.034,0.0056,0,0,0,0,0,0,0,0 +14790000,0.7,0.00032,-0.013,0.71,0.0036,-0.0019,-0.03,0.0038,-0.0032,-3.7e+02,-0.0011,-0.006,0.00016,-0.00093,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,2.5e-05,0.034,0.034,0.0053,0,0,0,0,0,0,0,0 +14890000,0.7,0.00031,-0.013,0.71,0.0052,-0.00087,-0.033,0.0042,-0.0034,-3.7e+02,-0.0011,-0.006,0.0002,-0.00091,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,6.9e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,2.4e-05,0.034,0.034,0.0051,0,0,0,0,0,0,0,0 +14990000,0.7,0.00031,-0.013,0.71,0.004,-0.0011,-0.029,0.0032,-0.0027,-3.7e+02,-0.0011,-0.006,0.00018,-0.00098,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.8e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,2.3e-05,0.034,0.034,0.0048,0,0,0,0,0,0,0,0 +15090000,0.7,0.00023,-0.013,0.71,0.0045,-0.0012,-0.032,0.0036,-0.0028,-3.7e+02,-0.0011,-0.006,0.00018,-0.00093,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,6.8e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,2.3e-05,0.034,0.034,0.0046,0,0,0,0,0,0,0,0 +15190000,0.7,0.00025,-0.013,0.71,0.0038,-6.2e-05,-0.029,0.0029,-0.0023,-3.7e+02,-0.0011,-0.006,0.00017,-0.00096,0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.7e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,2.2e-05,0.034,0.034,0.0043,0,0,0,0,0,0,0,0 +15290000,0.7,0.00021,-0.013,0.71,0.0044,0.00018,-0.027,0.0033,-0.0023,-3.7e+02,-0.0011,-0.006,0.00021,-0.001,0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.6e-05,0.045,0.045,0.03,0.053,0.053,0.052,2.2e-05,2.2e-05,2.1e-05,0.034,0.034,0.0042,0,0,0,0,0,0,0,0 +15390000,0.71,0.00021,-0.013,0.71,0.0037,0.00045,-0.024,0.00067,-0.0019,-3.7e+02,-0.0012,-0.006,0.0003,-0.0011,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.5e-05,0.039,0.039,0.029,0.047,0.047,0.051,2e-05,2e-05,2e-05,0.034,0.034,0.0039,0,0,0,0,0,0,0,0 +15490000,0.7,0.00023,-0.013,0.71,0.005,0.00015,-0.024,0.0011,-0.0019,-3.7e+02,-0.0012,-0.006,0.00025,-0.0011,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.5e-05,0.044,0.044,0.029,0.053,0.053,0.053,2e-05,2e-05,2e-05,0.034,0.034,0.0037,0,0,0,0,0,0,0,0 +15590000,0.7,0.00024,-0.013,0.71,0.003,7.8e-05,-0.023,-0.0012,-0.0016,-3.7e+02,-0.0012,-0.006,0.00022,-0.0011,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,1.9e-05,0.033,0.033,0.0035,0,0,0,0,0,0,0,0 +15690000,0.7,0.00025,-0.013,0.71,0.0034,-1.7e-05,-0.023,-0.00087,-0.0015,-3.7e+02,-0.0012,-0.006,0.00021,-0.0011,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.3e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,1.8e-05,0.033,0.033,0.0033,0,0,0,0,0,0,0,0 +15790000,0.7,0.00021,-0.013,0.71,0.0038,-0.0017,-0.026,-0.00083,-0.0026,-3.7e+02,-0.0012,-0.0061,0.00021,-0.0013,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.3e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,1.8e-05,0.033,0.033,0.0031,0,0,0,0,0,0,0,0 +15890000,0.7,0.00016,-0.013,0.71,0.0048,-0.0022,-0.024,-0.00037,-0.0029,-3.7e+02,-0.0012,-0.0061,0.00022,-0.0013,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.2e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,1.7e-05,0.033,0.033,0.003,0,0,0,0,0,0,0,0 +15990000,0.71,0.0001,-0.013,0.71,0.0046,-0.0031,-0.019,-0.0005,-0.0037,-3.7e+02,-0.0012,-0.0061,0.00028,-0.0016,0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.1e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,1.7e-05,0.033,0.033,0.0028,0,0,0,0,0,0,0,0 +16090000,0.71,0.0001,-0.013,0.71,0.0064,-0.0033,-0.016,4.1e-05,-0.004,-3.7e+02,-0.0012,-0.0061,0.00036,-0.0017,0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.1e-05,0.042,0.042,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,1.6e-05,0.033,0.033,0.0027,0,0,0,0,0,0,0,0 +16190000,0.71,0.00013,-0.013,0.71,0.0063,-0.0026,-0.014,-0.00022,-0.0033,-3.7e+02,-0.0012,-0.0061,0.00037,-0.0016,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00016,6e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,1.6e-05,0.033,0.033,0.0025,0,0,0,0,0,0,0,0 +16290000,0.71,0.00014,-0.013,0.71,0.008,-0.0033,-0.016,0.0005,-0.0036,-3.7e+02,-0.0012,-0.0061,0.00044,-0.0016,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6e-05,0.042,0.042,0.024,0.052,0.052,0.052,1.5e-05,1.5e-05,1.5e-05,0.033,0.033,0.0024,0,0,0,0,0,0,0,0 +16390000,0.71,0.00013,-0.013,0.71,0.0068,-0.0036,-0.015,0.00012,-0.0029,-3.7e+02,-0.0012,-0.0061,0.00042,-0.0015,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.9e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,1.5e-05,0.032,0.032,0.0022,0,0,0,0,0,0,0,0 +16490000,0.71,0.00015,-0.013,0.71,0.0061,-0.0031,-0.018,0.00074,-0.0032,-3.7e+02,-0.0012,-0.0061,0.00043,-0.0014,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00016,5.9e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,1.4e-05,0.032,0.032,0.0021,0,0,0,0,0,0,0,0 +16590000,0.71,0.0004,-0.013,0.71,0.0025,-0.00048,-0.018,-0.0023,0.00012,-3.7e+02,-0.0013,-0.006,0.00044,-0.00074,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.8e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,1.4e-05,0.032,0.032,0.002,0,0,0,0,0,0,0,0 +16690000,0.71,0.00039,-0.013,0.71,0.0027,4.3e-05,-0.015,-0.002,0.0001,-3.7e+02,-0.0013,-0.006,0.0004,-0.0008,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,1.4e-05,0.032,0.032,0.0019,0,0,0,0,0,0,0,0 +16790000,0.71,0.00054,-0.013,0.71,-0.00072,0.0022,-0.014,-0.0044,0.0027,-3.7e+02,-0.0013,-0.006,0.00041,-0.00021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,1.3e-05,0.032,0.032,0.0018,0,0,0,0,0,0,0,0 +16890000,0.71,0.00056,-0.013,0.71,-0.00095,0.0031,-0.011,-0.0045,0.003,-3.7e+02,-0.0013,-0.006,0.00039,-0.00025,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.6e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,1.3e-05,0.032,0.032,0.0017,0,0,0,0,0,0,0,0 +16990000,0.71,0.0005,-0.013,0.71,-0.00098,0.001,-0.01,-0.005,0.0011,-3.7e+02,-0.0013,-0.006,0.00035,-0.00065,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.6e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,1.2e-05,0.032,0.032,0.0016,0,0,0,0,0,0,0,0 +17090000,0.71,0.00046,-0.013,0.71,-0.00014,0.002,-0.01,-0.0051,0.0012,-3.7e+02,-0.0013,-0.006,0.00035,-0.00064,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.5e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,1.2e-05,0.032,0.032,0.0016,0,0,0,0,0,0,0,0 +17190000,0.71,0.00045,-0.013,0.71,0.00024,0.0019,-0.011,-0.0054,-0.00032,-3.7e+02,-0.0013,-0.006,0.00038,-0.00099,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.5e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,1.2e-05,0.031,0.031,0.0015,0,0,0,0,0,0,0,0 +17290000,0.71,0.00043,-0.013,0.71,0.0024,0.003,-0.0066,-0.0053,-9.1e-05,-3.7e+02,-0.0013,-0.006,0.00034,-0.001,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.4e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,1.2e-05,0.031,0.031,0.0014,0,0,0,0,0,0,0,0 +17390000,0.71,0.00039,-0.013,0.71,0.003,0.0021,-0.0047,-0.0045,-0.0014,-3.7e+02,-0.0013,-0.006,0.00038,-0.0014,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.4e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,1.1e-05,0.031,0.031,0.0013,0,0,0,0,0,0,0,0 +17490000,0.71,0.00039,-0.013,0.71,0.0035,0.0017,-0.003,-0.0042,-0.0012,-3.7e+02,-0.0013,-0.006,0.00038,-0.0014,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,1.1e-05,0.031,0.031,0.0013,0,0,0,0,0,0,0,0 +17590000,0.71,0.0003,-0.013,0.71,0.0047,0.0005,0.0025,-0.0035,-0.0024,-3.7e+02,-0.0013,-0.0061,0.00039,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,1.1e-05,0.031,0.031,0.0012,0,0,0,0,0,0,0,0 +17690000,0.71,0.00027,-0.013,0.71,0.0057,0.0013,0.0019,-0.003,-0.0023,-3.7e+02,-0.0013,-0.0061,0.00041,-0.0017,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.2e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,1e-05,0.031,0.031,0.0012,0,0,0,0,0,0,0,0 +17790000,0.71,0.00018,-0.013,0.71,0.0082,0.0009,0.00059,-0.0019,-0.002,-3.7e+02,-0.0013,-0.0061,0.00048,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.2e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,1e-05,0.031,0.031,0.0011,0,0,0,0,0,0,0,0 +17890000,0.71,0.00019,-0.013,0.71,0.0097,0.00018,0.00069,-0.00099,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00051,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.2e-05,0.037,0.037,0.016,0.051,0.051,0.048,7e-06,7e-06,9.8e-06,0.031,0.031,0.0011,0,0,0,0,0,0,0,0 +17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0016,0.0019,-0.00034,-0.0017,-3.7e+02,-0.0013,-0.0061,0.0005,-0.0017,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.1e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,9.6e-06,0.03,0.03,0.001,0,0,0,0,0,0,0,0 +18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0018,0.0043,0.00083,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00045,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.1e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,9.3e-06,0.03,0.03,0.00097,0,0,0,0,0,0,0,0 +18190000,0.71,0.0001,-0.013,0.71,0.013,-0.00074,0.0056,0.0016,-0.0015,-3.7e+02,-0.0013,-0.006,0.00048,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,9.1e-06,0.03,0.03,0.00092,0,0,0,0,0,0,0,0 +18290000,0.71,4.6e-05,-0.013,0.71,0.013,-0.0013,0.0068,0.0029,-0.0016,-3.7e+02,-0.0013,-0.006,0.00046,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,8.9e-06,0.03,0.03,0.00089,0,0,0,0,0,0,0,0 +18390000,0.71,6.1e-05,-0.013,0.71,0.014,0.00032,0.008,0.0034,-0.0012,-3.7e+02,-0.0013,-0.006,0.00049,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.9e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,8.6e-06,0.03,0.03,0.00084,0,0,0,0,0,0,0,0 +18490000,0.71,7.6e-05,-0.013,0.71,0.015,0.00077,0.0076,0.0049,-0.0011,-3.7e+02,-0.0013,-0.006,0.0005,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,4.9e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,8.5e-06,0.03,0.03,0.00082,0,0,0,0,0,0,0,0 +18590000,0.71,8.1e-05,-0.012,0.71,0.014,0.00095,0.0058,0.0037,-0.00098,-3.7e+02,-0.0013,-0.006,0.00054,-0.0016,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.9e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,8.2e-06,0.03,0.03,0.00078,0,0,0,0,0,0,0,0 +18690000,0.71,5e-05,-0.012,0.71,0.014,0.00029,0.0039,0.0051,-0.00089,-3.7e+02,-0.0013,-0.006,0.00053,-0.0016,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.8e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,8e-06,0.03,0.03,0.00075,0,0,0,0,0,0,0,0 +18790000,0.71,8.1e-05,-0.012,0.71,0.013,0.00054,0.0035,0.0039,-0.00071,-3.7e+02,-0.0014,-0.006,0.00051,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.8e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,7.9e-06,0.03,0.03,0.00072,0,0,0,0,0,0,0,0 +18890000,0.71,0.0001,-0.012,0.71,0.013,0.0011,0.0042,0.0052,-0.0006,-3.7e+02,-0.0014,-0.006,0.00056,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,7.7e-06,0.03,0.03,0.0007,0,0,0,0,0,0,0,0 +18990000,0.71,9.1e-05,-0.012,0.71,0.014,0.0019,0.0028,0.0065,-0.00051,-3.7e+02,-0.0014,-0.006,0.00057,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,7.5e-06,0.029,0.029,0.00066,0,0,0,0,0,0,0,0 +19090000,0.71,7.5e-05,-0.012,0.71,0.015,0.0025,0.0058,0.008,-0.00026,-3.7e+02,-0.0014,-0.006,0.00057,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,7.3e-06,0.029,0.03,0.00065,0,0,0,0,0,0,0,0 +19190000,0.71,7.7e-05,-0.012,0.71,0.015,0.0025,0.0059,0.0087,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00059,-0.0017,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,7.2e-06,0.029,0.029,0.00062,0,0,0,0,0,0,0,0 +19290000,0.71,0.0001,-0.012,0.71,0.015,0.0018,0.0086,0.01,-2.8e-05,-3.7e+02,-0.0014,-0.0061,0.00056,-0.0017,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,7e-06,0.029,0.029,0.0006,0,0,0,0,0,0,0,0 +19390000,0.71,0.00011,-0.012,0.71,0.013,0.0008,0.012,0.0082,-9.1e-05,-3.7e+02,-0.0014,-0.0061,0.00058,-0.0017,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.8e-06,0.029,0.029,0.00058,0,0,0,0,0,0,0,0 +19490000,0.71,0.00014,-0.012,0.71,0.012,0.00011,0.0088,0.0094,-4.9e-05,-3.7e+02,-0.0014,-0.0061,0.00061,-0.0017,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.7e-06,0.029,0.029,0.00056,0,0,0,0,0,0,0,0 +19590000,0.71,0.00018,-0.012,0.71,0.01,-0.00096,0.0081,0.0076,-0.00011,-3.7e+02,-0.0014,-0.0061,0.00065,-0.0017,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.5e-06,0.029,0.029,0.00054,0,0,0,0,0,0,0,0 +19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0031,0.0096,0.0086,-0.00032,-3.7e+02,-0.0014,-0.0061,0.00063,-0.0017,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.4e-06,0.029,0.029,0.00052,0,0,0,0,0,0,0,0 +19790000,0.71,0.00025,-0.012,0.71,0.008,-0.004,0.01,0.007,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00063,-0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.4e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19890000,0.71,0.0002,-0.012,0.71,0.0068,-0.0043,0.011,0.0077,-0.00069,-3.7e+02,-0.0014,-0.0061,0.00067,-0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.4e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19990000,0.71,0.00019,-0.012,0.71,0.0043,-0.005,0.014,0.0063,-0.00058,-3.7e+02,-0.0014,-0.006,0.00073,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.4e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20090000,0.71,0.00018,-0.012,0.71,0.0041,-0.0069,0.014,0.0067,-0.0012,-3.7e+02,-0.0014,-0.006,0.00078,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.0001,4.4e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,5.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20190000,0.71,0.00028,-0.012,0.71,0.0018,-0.0076,0.017,0.0044,-0.00092,-3.7e+02,-0.0014,-0.006,0.0008,-0.0015,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,5.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20290000,0.71,0.00024,-0.012,0.71,0.00064,-0.0092,0.015,0.0045,-0.0018,-3.7e+02,-0.0014,-0.006,0.00081,-0.0015,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,5.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20390000,0.71,0.00026,-0.012,0.71,-0.0019,-0.0098,0.017,0.0026,-0.0014,-3.7e+02,-0.0014,-0.006,0.00081,-0.0013,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,5.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20490000,0.71,0.00032,-0.012,0.71,-0.0023,-0.011,0.016,0.0024,-0.0024,-3.7e+02,-0.0014,-0.006,0.00079,-0.0013,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,5.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20590000,0.71,0.00034,-0.012,0.71,-0.002,-0.011,0.013,0.002,-0.0019,-3.7e+02,-0.0014,-0.006,0.00077,-0.0011,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.9e-05,9.9e-05,4.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,5.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20690000,0.71,0.00037,-0.012,0.71,-0.002,-0.012,0.015,0.0018,-0.003,-3.7e+02,-0.0014,-0.006,0.00078,-0.0011,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,5.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20790000,0.71,0.00039,-0.012,0.71,-0.0031,-0.011,0.015,0.0015,-0.0024,-3.7e+02,-0.0014,-0.006,0.00078,-0.00095,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.8e-05,9.7e-05,4.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,5.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20890000,0.71,0.00038,-0.012,0.71,-0.0035,-0.013,0.014,0.0012,-0.0036,-3.7e+02,-0.0014,-0.006,0.00081,-0.00096,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.8e-05,9.8e-05,4.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20990000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.015,0.0028,-0.003,-3.7e+02,-0.0014,-0.006,0.00081,-0.00076,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.6e-05,9.6e-05,4.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,4.9e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21090000,0.71,0.00038,-0.012,0.71,-0.0039,-0.017,0.015,0.0024,-0.0045,-3.7e+02,-0.0014,-0.006,0.00082,-0.00076,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.7e-05,9.7e-05,4.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,4.8e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21190000,0.71,0.00042,-0.012,0.71,-0.0032,-0.015,0.014,0.0039,-0.0036,-3.7e+02,-0.0014,-0.006,0.00081,-0.00053,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.5e-05,9.5e-05,4e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,4.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21290000,0.71,0.00046,-0.012,0.71,-0.0037,-0.018,0.016,0.0035,-0.0053,-3.7e+02,-0.0014,-0.006,0.00084,-0.00053,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.6e-05,9.5e-05,4e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,4.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21390000,0.71,0.0005,-0.012,0.71,-0.0046,-0.017,0.016,0.003,-0.0033,-3.7e+02,-0.0014,-0.006,0.00082,-0.00016,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.4e-05,9.4e-05,4e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,4.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21490000,0.71,0.00051,-0.012,0.71,-0.0051,-0.018,0.015,0.0025,-0.005,-3.7e+02,-0.0014,-0.006,0.00083,-0.00016,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.4e-05,9.4e-05,4e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,4.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21590000,0.71,0.00053,-0.012,0.71,-0.0056,-0.015,0.015,0.002,-0.003,-3.7e+02,-0.0014,-0.006,0.00082,0.00018,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.3e-05,9.3e-05,3.9e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,4.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21690000,0.71,0.00054,-0.012,0.71,-0.0055,-0.016,0.017,0.0015,-0.0046,-3.7e+02,-0.0014,-0.006,0.00083,0.00018,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.3e-05,9.3e-05,3.9e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,4.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21790000,0.71,0.00056,-0.012,0.71,-0.0061,-0.011,0.015,0.00019,-0.00063,-3.7e+02,-0.0014,-0.0059,0.0008,0.00071,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.2e-05,9.2e-05,3.9e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.2e-06,4.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21890000,0.71,0.00056,-0.012,0.71,-0.0061,-0.012,0.016,-0.00042,-0.0018,-3.7e+02,-0.0014,-0.0059,0.0008,0.0007,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.2e-05,9.2e-05,3.9e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,4.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21990000,0.71,0.00061,-0.012,0.71,-0.0066,-0.0089,0.016,-0.0014,0.0016,-3.7e+02,-0.0014,-0.0059,0.00079,0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.1e-05,9.1e-05,3.9e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22090000,0.71,0.00063,-0.012,0.71,-0.0069,-0.008,0.015,-0.002,0.00076,-3.7e+02,-0.0014,-0.0059,0.00078,0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.1e-05,9.1e-05,3.8e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22190000,0.71,0.0006,-0.012,0.71,-0.0068,-0.0072,0.015,-0.0017,0.0007,-3.7e+02,-0.0014,-0.0059,0.00078,0.0012,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,9e-05,3.8e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,3.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22290000,0.71,0.00064,-0.012,0.71,-0.0081,-0.0079,0.015,-0.0024,-6.3e-05,-3.7e+02,-0.0014,-0.0059,0.00077,0.0012,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,9e-05,3.8e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,3.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22390000,0.71,0.00061,-0.012,0.71,-0.0087,-0.0074,0.017,-0.0021,-7.2e-05,-3.7e+02,-0.0014,-0.0059,0.00077,0.0013,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.9e-05,8.9e-05,3.8e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22490000,0.71,0.00062,-0.012,0.71,-0.0093,-0.0073,0.018,-0.003,-0.00083,-3.7e+02,-0.0014,-0.0059,0.00077,0.0013,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,8.9e-05,3.7e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22590000,0.71,0.0006,-0.012,0.71,-0.0091,-0.0068,0.017,-0.0033,0.00024,-3.7e+02,-0.0014,-0.0059,0.00076,0.0014,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.7e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,3.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22690000,0.71,0.00063,-0.012,0.71,-0.01,-0.0066,0.018,-0.0042,-0.00043,-3.7e+02,-0.0014,-0.0059,0.00077,0.0014,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.9e-05,8.9e-05,3.7e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,3.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0054,0.019,-0.0054,-0.00034,-3.7e+02,-0.0014,-0.0059,0.00073,0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.7e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,3.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.005,0.021,-0.0065,-0.00086,-3.7e+02,-0.0014,-0.0059,0.00072,0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.6e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,3.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0055,0.022,-0.0073,-0.00077,-3.7e+02,-0.0014,-0.0059,0.00073,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.7e-05,3.6e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,3.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23090000,0.71,0.00057,-0.012,0.71,-0.013,-0.0055,0.022,-0.0086,-0.0013,-3.7e+02,-0.0014,-0.0059,0.0007,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.7e-05,3.6e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,3.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23190000,0.71,0.00064,-0.012,0.71,-0.014,-0.0064,0.024,-0.012,-0.0012,-3.7e+02,-0.0014,-0.0059,0.00069,0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.6e-05,3.6e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,3.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0077,0.024,-0.013,-0.0019,-3.7e+02,-0.0014,-0.0059,0.00069,0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.7e-05,3.6e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,3.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.0079,0.022,-0.016,-0.0017,-3.7e+02,-0.0014,-0.0059,0.00069,0.0017,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.6e-05,8.6e-05,3.5e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,3.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0088,-0.012,-0.018,-0.0025,-3.7e+02,-0.0014,-0.0059,0.00069,0.0017,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.6e-05,3.5e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,3.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23590000,0.71,0.0083,-0.0018,0.71,-0.033,-0.0075,-0.044,-0.016,-0.0012,-3.7e+02,-0.0014,-0.0059,0.00068,0.0019,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.7e-05,8.5e-05,3.5e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0023,-3.7e+02,-0.0014,-0.0059,0.00067,0.0019,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.8e-05,8.5e-05,3.5e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23790000,0.71,0.005,0.00064,0.71,-0.088,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-0.0014,-0.0059,0.00068,0.0021,0.0064,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.6e-05,8.4e-05,3.5e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,2.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.0049,-3.7e+02,-0.0014,-0.0059,0.00067,0.0021,0.0064,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.6e-05,8.5e-05,3.4e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,2.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.039,-0.25,-0.034,-0.0081,-3.7e+02,-0.0014,-0.0059,0.00067,0.0022,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.4e-05,3.4e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,2.9e-06,0.028,0.028,0.0005,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,-0.0014,-0.0059,0.00068,0.0022,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.5e-05,8.4e-05,3.4e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-07,6.7e-07,2.8e-06,0.028,0.028,0.0005,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,-0.0014,-0.0059,0.00068,0.0024,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.4e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-07,6.4e-07,2.8e-06,0.028,0.028,0.0005,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,-0.0014,-0.0059,0.00067,0.0024,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.5e-05,8.4e-05,3.4e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.4e-07,2.7e-06,0.028,0.028,0.0005,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,-0.0013,-0.0059,0.00065,0.0021,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,2.7e-06,0.028,0.028,0.0005,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,-0.0013,-0.0059,0.00065,0.0021,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.3e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24590000,0.71,0.0051,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,0.00066,0.002,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,2.6e-06,0.028,0.028,0.0005,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,-0.0013,-0.0059,0.00067,0.002,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.3e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,2.6e-06,0.028,0.028,0.0005,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,-0.0013,-0.0059,0.00065,0.0024,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24890000,0.71,0.0066,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,0.00064,0.0024,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.2e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24990000,0.71,0.0084,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,0.00063,0.0032,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25090000,0.71,0.0087,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,0.00061,0.0033,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.2e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,2.4e-06,0.028,0.028,0.0005,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,-0.0013,-0.0059,0.00062,0.0029,0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.2e-05,8e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.3e-07,5.2e-07,2.4e-06,0.028,0.028,0.0005,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,-0.0013,-0.0059,0.00062,0.0029,0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8e-05,3.2e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,2.3e-06,0.028,0.028,0.0005,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,-0.0012,-0.0059,0.00062,0.003,-4.5e-06,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,7.9e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,2.3e-06,0.028,0.028,0.0005,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,-0.0012,-0.0059,0.00063,0.003,5.6e-06,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,7.9e-05,3.2e-05,0.019,0.018,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,2.3e-06,0.028,0.028,0.0005,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,-0.0012,-0.0059,0.00063,0.0027,-0.00089,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.2e-05,7.8e-05,3.1e-05,0.017,0.016,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,2.2e-06,0.028,0.028,0.0005,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,-0.0012,-0.0059,0.00064,0.0027,-0.00087,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.4e-05,7.9e-05,3.1e-05,0.019,0.018,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,0.00065,0.0034,-0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.4e-05,7.8e-05,3.1e-05,0.018,0.016,0.0079,0.04,0.04,0.035,4.8e-07,4.7e-07,2.2e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25890000,0.7,0.017,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,0.00067,0.0034,-0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.5e-05,7.8e-05,3.1e-05,0.02,0.018,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,2.1e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25990000,0.7,0.016,0.025,0.71,-0.65,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,0.00068,0.003,-0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0035,8.2e-05,7.7e-05,3.1e-05,0.019,0.017,0.0079,0.04,0.04,0.035,4.7e-07,4.6e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,0.00067,0.003,-0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0035,8.5e-05,7.7e-05,3.1e-05,0.021,0.018,0.008,0.044,0.044,0.035,4.7e-07,4.6e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,0.00068,0.0042,-0.0085,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0034,8.6e-05,7.7e-05,3e-05,0.02,0.017,0.0079,0.04,0.04,0.035,4.6e-07,4.5e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26290000,0.7,0.024,0.047,0.71,-0.86,-0.44,-1.3,-0.61,-0.47,-3.7e+02,-0.0011,-0.0059,0.00068,0.0042,-0.0085,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0034,8.7e-05,7.7e-05,3e-05,0.023,0.018,0.008,0.044,0.044,0.035,4.6e-07,4.5e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26390000,0.7,0.023,0.044,0.71,-0.94,-0.5,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,0.0007,0.0029,-0.0098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0033,8.4e-05,7.6e-05,3e-05,0.022,0.017,0.0079,0.04,0.04,0.035,4.5e-07,4.4e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26490000,0.7,0.03,0.059,0.71,-1,-0.54,-1.3,-0.77,-0.6,-3.7e+02,-0.001,-0.0059,0.00071,0.0029,-0.0098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0033,9.1e-05,7.6e-05,3e-05,0.025,0.019,0.008,0.045,0.044,0.035,4.5e-07,4.4e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26590000,0.7,0.036,0.075,0.71,-1.1,-0.6,-1.3,-0.82,-0.67,-3.7e+02,-0.00097,-0.0059,0.00069,0.004,-0.013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0031,9.5e-05,7.6e-05,3e-05,0.024,0.017,0.008,0.04,0.039,0.035,4.4e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26690000,0.7,0.037,0.078,0.71,-1.3,-0.66,-1.3,-0.94,-0.73,-3.7e+02,-0.00097,-0.0059,0.00072,0.0039,-0.013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0031,9.7e-05,7.6e-05,3e-05,0.029,0.019,0.008,0.045,0.044,0.035,4.4e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26790000,0.7,0.035,0.073,0.71,-1.4,-0.75,-1.3,-1,-0.86,-3.7e+02,-0.00093,-0.006,0.00073,0.0019,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0029,9.1e-05,7.5e-05,3e-05,0.028,0.018,0.008,0.041,0.039,0.035,4.4e-07,4.2e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26890000,0.7,0.044,0.095,0.71,-1.5,-0.81,-1.3,-1.2,-0.94,-3.7e+02,-0.00093,-0.006,0.00076,0.0018,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0001,7.6e-05,3e-05,0.033,0.021,0.0081,0.046,0.044,0.035,4.4e-07,4.2e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26990000,0.69,0.049,0.12,0.71,-1.6,-0.91,-1.3,-1.2,-1,-3.7e+02,-0.00085,-0.0059,0.00079,0.0032,-0.019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.00011,7.7e-05,3e-05,0.032,0.02,0.0081,0.041,0.04,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27090000,0.69,0.05,0.12,0.71,-1.8,-1,-1.3,-1.4,-1.1,-3.7e+02,-0.00084,-0.0059,0.00083,0.0031,-0.02,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.00011,7.7e-05,3e-05,0.039,0.022,0.0082,0.046,0.044,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27190000,0.7,0.047,0.11,0.71,-2.1,-1.1,-1.2,-1.6,-1.2,-3.7e+02,-0.00083,-0.0059,0.00087,0.004,-0.02,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.8e-05,7.6e-05,3e-05,0.04,0.023,0.0082,0.049,0.046,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27290000,0.7,0.042,0.094,0.71,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00083,-0.0059,0.0009,0.0039,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.2e-05,7.5e-05,3e-05,0.046,0.025,0.0082,0.056,0.051,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27390000,0.7,0.036,0.078,0.71,-2.3,-1.2,-1.2,-2,-1.4,-3.7e+02,-0.00079,-0.0058,0.00095,0.0063,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0021,8.3e-05,7.4e-05,2.9e-05,0.043,0.025,0.0082,0.057,0.054,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27490000,0.7,0.03,0.063,0.71,-2.4,-1.2,-1.2,-2.2,-1.5,-3.7e+02,-0.00078,-0.0058,0.00098,0.0062,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0021,8e-05,7.4e-05,2.9e-05,0.047,0.027,0.0083,0.065,0.059,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27590000,0.7,0.026,0.05,0.71,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-0.00077,-0.0058,0.001,0.0056,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0018,7.7e-05,7.4e-05,2.9e-05,0.041,0.025,0.0082,0.067,0.062,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27690000,0.7,0.025,0.049,0.71,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00077,-0.0058,0.001,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0018,7.6e-05,7.4e-05,2.9e-05,0.043,0.027,0.0083,0.075,0.068,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27790000,0.71,0.026,0.05,0.71,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-0.00076,-0.0058,0.001,0.0055,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0016,7.6e-05,7.4e-05,2.8e-05,0.038,0.026,0.0083,0.076,0.07,0.035,4.3e-07,4e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27890000,0.71,0.025,0.048,0.71,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-0.00076,-0.0058,0.001,0.0053,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0016,7.6e-05,7.4e-05,2.8e-05,0.04,0.028,0.0084,0.085,0.077,0.036,4.3e-07,4e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27990000,0.71,0.024,0.044,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-0.00076,-0.0058,0.001,0.0044,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,7.5e-05,7.4e-05,2.8e-05,0.035,0.026,0.0083,0.085,0.079,0.035,4.3e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,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,-0.00076,-0.0058,0.00097,0.0044,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,7.6e-05,7.4e-05,2.8e-05,0.037,0.028,0.0084,0.095,0.087,0.035,4.3e-07,4e-07,1.6e-06,0.027,0.027,0.0005,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,-0.00076,-0.0058,0.00096,0.0039,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,7.3e-05,2.8e-05,0.033,0.026,0.0084,0.095,0.088,0.035,4.3e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28290000,0.71,0.027,0.054,0.7,-2.8,-1.3,-0.087,-4.5,-2.4,-3.7e+02,-0.00076,-0.0058,0.00093,0.0038,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.5e-05,7.4e-05,2.8e-05,0.034,0.027,0.0086,0.1,0.096,0.036,4.3e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28390000,0.71,0.011,0.022,0.7,-2.8,-1.3,0.77,-4.8,-2.6,-3.7e+02,-0.00076,-0.0058,0.00091,0.0035,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.5e-05,7.4e-05,2.8e-05,0.035,0.028,0.0087,0.11,0.1,0.036,4.3e-07,3.9e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28490000,0.71,0.0021,0.0042,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-0.00076,-0.0058,0.00089,0.0033,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,7.5e-05,2.7e-05,0.035,0.029,0.0088,0.13,0.11,0.036,4.3e-07,3.9e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28590000,0.71,0.00035,0.00071,0.7,-2.7,-1.3,0.96,-5.3,-2.8,-3.7e+02,-0.00076,-0.0058,0.00088,0.003,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.5e-05,2.7e-05,0.035,0.03,0.0089,0.14,0.12,0.036,4.4e-07,4e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28690000,0.71,-0.00036,-0.00021,0.7,-2.6,-1.2,0.97,-5.6,-2.9,-3.7e+02,-0.00076,-0.0058,0.00087,0.0026,-0.015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.5e-05,2.7e-05,0.035,0.032,0.009,0.15,0.13,0.036,4.4e-07,4e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28790000,0.71,-0.00085,-0.00057,0.7,-2.6,-1.2,0.97,-5.9,-3,-3.7e+02,-0.00078,-0.0058,0.00084,-0.00053,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.5e-05,2.7e-05,0.031,0.029,0.0089,0.15,0.13,0.036,4.3e-07,3.9e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28890000,0.71,-0.00087,-0.00036,0.7,-2.5,-1.2,0.96,-6.2,-3.1,-3.7e+02,-0.00078,-0.0058,0.00082,-0.00091,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.5e-05,2.7e-05,0.031,0.03,0.009,0.16,0.14,0.036,4.4e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28990000,0.72,-0.00085,-1.5e-05,0.7,-2.5,-1.2,0.95,-6.5,-3.2,-3.7e+02,-0.00082,-0.0058,0.00077,-0.0026,-0.029,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.5e-05,2.7e-05,0.028,0.028,0.009,0.16,0.14,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29090000,0.72,-0.0007,0.00037,0.7,-2.4,-1.1,0.94,-6.8,-3.4,-3.7e+02,-0.00082,-0.0058,0.00074,-0.003,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.7e-05,0.029,0.029,0.009,0.17,0.15,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29190000,0.72,-0.00056,0.00074,0.7,-2.4,-1.1,0.94,-7.1,-3.5,-3.7e+02,-0.00085,-0.0058,0.00071,-0.0043,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.7e-05,0.027,0.028,0.009,0.17,0.15,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29290000,0.72,-0.0002,0.0016,0.7,-2.3,-1.1,0.96,-7.3,-3.6,-3.7e+02,-0.00085,-0.0058,0.00067,-0.0048,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.6e-05,0.027,0.029,0.0091,0.18,0.16,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29390000,0.72,0.0003,0.003,0.7,-2.3,-1.1,0.97,-7.6,-3.7,-3.7e+02,-0.00089,-0.0058,0.00061,-0.0055,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.025,0.027,0.009,0.17,0.16,0.036,4.3e-07,3.8e-07,1.4e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +29490000,0.72,0.00082,0.0041,0.7,-2.3,-1.1,0.97,-7.9,-3.8,-3.7e+02,-0.00089,-0.0058,0.00058,-0.0059,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.026,0.028,0.0091,0.19,0.17,0.037,4.3e-07,3.8e-07,1.4e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +29590000,0.72,0.0012,0.0052,0.7,-2.2,-1.1,0.96,-8.1,-3.9,-3.7e+02,-0.00092,-0.0058,0.00054,-0.0076,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.025,0.027,0.009,0.18,0.17,0.036,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +29690000,0.72,0.0015,0.0058,0.7,-2.2,-1.1,0.95,-8.3,-4,-3.7e+02,-0.00092,-0.0058,0.0005,-0.008,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.028,0.0091,0.2,0.18,0.036,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +29790000,0.72,0.0018,0.0063,0.7,-2.2,-1.1,0.94,-8.6,-4.1,-3.7e+02,-0.00095,-0.0058,0.00047,-0.009,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.025,0.026,0.0091,0.19,0.18,0.037,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +29890000,0.72,0.0018,0.0065,0.7,-2.1,-1.1,0.93,-8.8,-4.2,-3.7e+02,-0.00095,-0.0058,0.00042,-0.0097,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.21,0.19,0.037,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +29990000,0.72,0.002,0.0067,0.7,-2.1,-1,0.91,-9.1,-4.3,-3.7e+02,-0.00098,-0.0058,0.00038,-0.011,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.025,0.026,0.009,0.2,0.19,0.036,4.1e-07,3.7e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30090000,0.72,0.002,0.0066,0.7,-2.1,-1,0.89,-9.3,-4.4,-3.7e+02,-0.00098,-0.0058,0.00034,-0.012,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.22,0.2,0.036,4.1e-07,3.7e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30190000,0.72,0.002,0.0065,0.7,-2.1,-1,0.88,-9.6,-4.5,-3.7e+02,-0.001,-0.0058,0.00031,-0.013,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.5e-05,2.6e-05,0.025,0.026,0.009,0.21,0.2,0.037,4.1e-07,3.7e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30290000,0.72,0.0019,0.0063,0.7,-2,-1,0.87,-9.8,-4.6,-3.7e+02,-0.001,-0.0058,0.00027,-0.013,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.22,0.21,0.037,4.1e-07,3.7e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30390000,0.72,0.0019,0.0061,0.7,-2,-1,0.85,-10,-4.7,-3.7e+02,-0.001,-0.0058,0.00023,-0.014,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.6e-05,0.025,0.026,0.009,0.22,0.21,0.036,4e-07,3.7e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30490000,0.72,0.0018,0.0059,0.7,-2,-1,0.84,-10,-4.8,-3.7e+02,-0.001,-0.0058,0.00021,-0.014,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.6e-05,0.026,0.027,0.0091,0.23,0.22,0.037,4e-07,3.7e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30590000,0.72,0.0018,0.0056,0.7,-1.9,-1,0.8,-10,-4.9,-3.7e+02,-0.0011,-0.0058,0.00018,-0.015,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.025,0.025,0.009,0.23,0.22,0.037,4e-07,3.6e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30690000,0.72,0.0016,0.0052,0.7,-1.9,-1,0.79,-11,-5,-3.7e+02,-0.0011,-0.0058,0.00015,-0.015,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.027,0.027,0.009,0.24,0.23,0.037,4e-07,3.6e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +30790000,0.72,0.0016,0.0049,0.7,-1.9,-0.99,0.78,-11,-5.1,-3.7e+02,-0.0011,-0.0058,0.00011,-0.016,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.026,0.025,0.0089,0.24,0.23,0.037,3.9e-07,3.6e-07,1.2e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +30890000,0.72,0.0014,0.0045,0.7,-1.9,-0.98,0.77,-11,-5.2,-3.7e+02,-0.0011,-0.0058,8.4e-05,-0.016,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.027,0.027,0.009,0.25,0.24,0.037,3.9e-07,3.6e-07,1.2e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +30990000,0.72,0.0014,0.004,0.7,-1.8,-0.97,0.76,-11,-5.3,-3.7e+02,-0.0011,-0.0058,5e-05,-0.016,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.026,0.025,0.0089,0.25,0.24,0.036,3.8e-07,3.6e-07,1.2e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31090000,0.72,0.0012,0.0035,0.7,-1.8,-0.96,0.75,-11,-5.4,-3.7e+02,-0.0011,-0.0058,2.1e-05,-0.017,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.027,0.026,0.0089,0.26,0.25,0.037,3.8e-07,3.6e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31190000,0.72,0.0012,0.0033,0.7,-1.8,-0.96,0.74,-12,-5.4,-3.7e+02,-0.0011,-0.0058,-8e-06,-0.018,-0.017,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.026,0.025,0.0088,0.26,0.25,0.037,3.8e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31290000,0.72,0.00094,0.0027,0.7,-1.8,-0.95,0.74,-12,-5.5,-3.7e+02,-0.0011,-0.0058,-3.2e-05,-0.019,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.028,0.026,0.0089,0.27,0.26,0.037,3.8e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31390000,0.72,0.00087,0.0023,0.7,-1.7,-0.94,0.73,-12,-5.6,-3.7e+02,-0.0012,-0.0058,-6.1e-05,-0.019,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.026,0.025,0.0087,0.27,0.26,0.036,3.7e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31490000,0.72,0.00065,0.0016,0.7,-1.7,-0.93,0.73,-12,-5.7,-3.7e+02,-0.0012,-0.0058,-9.1e-05,-0.02,-0.013,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.028,0.026,0.0088,0.28,0.27,0.037,3.7e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31590000,0.72,0.00064,0.0013,0.7,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-0.0012,-0.0057,-0.00011,-0.02,-0.011,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.027,0.025,0.0087,0.28,0.27,0.037,3.6e-07,3.4e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31690000,0.72,0.00038,0.00063,0.7,-1.6,-0.91,0.73,-13,-5.9,-3.7e+02,-0.0012,-0.0057,-0.00013,-0.021,-0.01,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.028,0.026,0.0087,0.29,0.28,0.037,3.6e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31790000,0.71,0.00026,2.7e-05,0.7,-1.6,-0.9,0.73,-13,-6,-3.7e+02,-0.0012,-0.0057,-0.00015,-0.022,-0.0082,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.027,0.025,0.0087,0.29,0.27,0.037,3.5e-07,3.4e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31890000,0.71,7.3e-06,-0.00068,0.7,-1.6,-0.89,0.72,-13,-6.1,-3.7e+02,-0.0012,-0.0057,-0.00017,-0.022,-0.007,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.029,0.026,0.0087,0.3,0.29,0.037,3.5e-07,3.4e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +31990000,0.71,-7.7e-05,-0.0011,0.7,-1.6,-0.88,0.71,-13,-6.2,-3.7e+02,-0.0012,-0.0057,-0.0002,-0.023,-0.0052,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.027,0.025,0.0086,0.3,0.28,0.036,3.5e-07,3.4e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +32090000,0.71,-0.00037,-0.0019,0.7,-1.5,-0.87,0.72,-13,-6.2,-3.7e+02,-0.0012,-0.0057,-0.00022,-0.024,-0.0037,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.029,0.026,0.0087,0.31,0.3,0.037,3.5e-07,3.4e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +32190000,0.71,-0.00051,-0.0026,0.7,-1.5,-0.86,0.72,-13,-6.3,-3.7e+02,-0.0013,-0.0057,-0.00025,-0.024,-0.0017,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0085,0.31,0.29,0.036,3.4e-07,3.3e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +32290000,0.71,-0.00075,-0.0034,0.7,-1.5,-0.85,0.71,-14,-6.4,-3.7e+02,-0.0013,-0.0057,-0.00027,-0.025,-0.00014,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.2e-05,7.3e-05,2.4e-05,0.029,0.026,0.0086,0.32,0.31,0.036,3.4e-07,3.3e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +32390000,0.71,-0.00089,-0.004,0.7,-1.5,-0.84,0.71,-14,-6.5,-3.7e+02,-0.0013,-0.0057,-0.00028,-0.025,0.00072,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0085,0.32,0.3,0.037,3.3e-07,3.3e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 +32490000,0.71,-0.001,-0.0042,0.7,-1.4,-0.82,0.72,-14,-6.6,-3.7e+02,-0.0013,-0.0057,-0.00029,-0.026,0.0018,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.03,0.026,0.0085,0.33,0.32,0.037,3.3e-07,3.3e-07,1e-06,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +32590000,0.71,-0.00094,-0.0044,0.7,-1.4,-0.81,0.72,-14,-6.7,-3.7e+02,-0.0013,-0.0057,-0.00031,-0.026,0.0026,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0084,0.33,0.31,0.036,3.3e-07,3.2e-07,9.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +32690000,0.71,-0.00099,-0.0045,0.7,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-0.0013,-0.0057,-0.00032,-0.026,0.0032,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.03,0.026,0.0085,0.34,0.32,0.036,3.3e-07,3.2e-07,9.8e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +32790000,0.71,-0.0009,-0.0045,0.7,-1.3,-0.79,0.71,-14,-6.8,-3.7e+02,-0.0013,-0.0057,-0.00034,-0.027,0.0041,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.1e-05,7.2e-05,2.3e-05,0.028,0.025,0.0084,0.34,0.32,0.036,3.2e-07,3.2e-07,9.7e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +32890000,0.71,-0.00081,-0.0044,0.7,-1.3,-0.78,0.71,-14,-6.9,-3.7e+02,-0.0013,-0.0057,-0.00036,-0.027,0.0051,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.1e-05,7.2e-05,2.3e-05,0.03,0.026,0.0084,0.35,0.33,0.036,3.2e-07,3.2e-07,9.6e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +32990000,0.71,-0.00061,-0.0044,0.7,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-0.0013,-0.0057,-0.00036,-0.028,0.0065,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.1e-05,7.2e-05,2.3e-05,0.028,0.025,0.0083,0.35,0.33,0.036,3.1e-07,3.2e-07,9.5e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33090000,0.71,-0.00065,-0.0044,0.7,-1.3,-0.76,0.7,-15,-7.1,-3.7e+02,-0.0013,-0.0057,-0.00036,-0.028,0.007,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.1e-05,7.2e-05,2.3e-05,0.03,0.026,0.0084,0.36,0.34,0.036,3.1e-07,3.2e-07,9.4e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33190000,0.71,0.0028,-0.0034,0.71,-1.2,-0.75,0.64,-15,-7.1,-3.7e+02,-0.0013,-0.0057,-0.00037,-0.028,0.0078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8e-05,7.2e-05,2.3e-05,0.028,0.025,0.0083,0.36,0.34,0.036,3.1e-07,3.1e-07,9.3e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33290000,0.66,0.015,-0.0025,0.76,-1.2,-0.73,0.62,-15,-7.2,-3.7e+02,-0.0013,-0.0057,-0.00037,-0.028,0.0082,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,7.9e-05,7.3e-05,2.5e-05,0.03,0.026,0.0083,0.37,0.35,0.036,3.1e-07,3.1e-07,9.2e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33390000,0.55,0.013,-0.0027,0.83,-1.2,-0.72,0.81,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00037,-0.029,0.0092,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00091,7.8e-05,7.3e-05,5.2e-05,0.028,0.025,0.0083,0.37,0.35,0.036,3e-07,3.1e-07,9.2e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33490000,0.41,0.0061,-0.00013,0.91,-1.2,-0.71,0.83,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00038,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00083,7.7e-05,7.5e-05,0.00012,0.03,0.026,0.0081,0.38,0.36,0.036,3e-07,3.1e-07,9.1e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33590000,0.26,0.00013,-0.0025,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00068,7.5e-05,7.6e-05,0.00023,0.029,0.026,0.0078,0.38,0.36,0.036,3e-07,3e-07,9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33690000,0.09,-0.0033,-0.0054,1,-1.1,-0.71,0.8,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00051,7.4e-05,7.8e-05,0.00035,0.032,0.029,0.0076,0.39,0.37,0.036,2.9e-07,3e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33790000,-0.081,-0.0048,-0.0071,1,-1.1,-0.69,0.78,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00032,7.1e-05,7.8e-05,0.00042,0.031,0.029,0.0074,0.38,0.36,0.036,2.9e-07,2.9e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33890000,-0.25,-0.0059,-0.0077,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7e-05,7.9e-05,0.00043,0.035,0.032,0.0072,0.39,0.38,0.036,2.8e-07,2.9e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +33990000,-0.39,-0.0041,-0.011,0.92,-0.96,-0.63,0.74,-16,-7.7,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,6.7e-05,7.6e-05,0.00039,0.034,0.032,0.007,0.38,0.37,0.035,2.8e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +34090000,-0.5,-0.003,-0.013,0.87,-0.9,-0.58,0.74,-16,-7.7,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,4.8e-05,6.7e-05,7.5e-05,0.00034,0.038,0.037,0.0069,0.39,0.38,0.036,2.8e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +34190000,-0.57,-0.0023,-0.011,0.82,-0.89,-0.54,0.74,-16,-7.8,-3.7e+02,-0.0014,-0.0057,-0.00038,-0.032,0.011,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,6.3e-05,7.1e-05,0.00028,0.038,0.037,0.0067,0.39,0.38,0.035,2.7e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +34290000,-0.61,-0.0032,-0.0086,0.79,-0.84,-0.49,0.74,-16,-7.9,-3.7e+02,-0.0014,-0.0057,-0.00038,-0.032,0.011,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,6.4e-05,7e-05,0.00024,0.043,0.043,0.0066,0.4,0.39,0.035,2.7e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +34390000,-0.64,-0.0033,-0.0061,0.77,-0.83,-0.45,0.74,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00038,-0.037,0.016,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,5.9e-05,6.5e-05,0.00021,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-07,2.7e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +34490000,-0.65,-0.0042,-0.0039,0.76,-0.77,-0.41,0.73,-16,-8,-3.7e+02,-0.0015,-0.0057,-0.00038,-0.037,0.016,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.9e-05,6.5e-05,0.00018,0.049,0.05,0.0064,0.41,0.4,0.035,2.7e-07,2.7e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 +34590000,-0.66,-0.0035,-0.0028,0.75,-0.78,-0.39,0.73,-17,-8,-3.7e+02,-0.0015,-0.0057,-0.00037,-0.047,0.025,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.4e-05,5.9e-05,0.00016,0.047,0.048,0.0063,0.4,0.4,0.034,2.7e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 +34690000,-0.67,-0.0039,-0.0021,0.74,-0.72,-0.35,0.73,-17,-8.1,-3.7e+02,-0.0015,-0.0057,-0.00037,-0.047,0.025,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.4e-05,5.9e-05,0.00015,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 +34790000,-0.67,-0.0027,-0.0018,0.74,-0.73,-0.34,0.72,-17,-8.2,-3.7e+02,-0.0015,-0.0057,-0.00036,-0.059,0.036,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,4.9e-05,5.3e-05,0.00013,0.051,0.052,0.0062,0.41,0.41,0.034,2.6e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 +34890000,-0.68,-0.0028,-0.0017,0.74,-0.68,-0.31,0.72,-17,-8.2,-3.7e+02,-0.0015,-0.0057,-0.00036,-0.059,0.036,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.9e-05,5.3e-05,0.00012,0.058,0.06,0.0062,0.42,0.42,0.034,2.7e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 +34990000,-0.68,-0.009,-0.0045,0.73,0.33,0.3,-0.13,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00036,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,0.00011,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-07,2.7e-07,8.9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35090000,-0.68,-0.009,-0.0046,0.73,0.45,0.33,-0.18,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,0.0001,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-07,2.7e-07,8.9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35190000,-0.68,-0.009,-0.0046,0.73,0.48,0.36,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,9.7e-05,0.067,0.068,0.0067,0.44,0.44,0.034,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35290000,-0.68,-0.0091,-0.0047,0.73,0.5,0.39,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,9.1e-05,0.072,0.074,0.0066,0.46,0.45,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35390000,-0.68,-0.0091,-0.0046,0.73,0.52,0.43,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,8.6e-05,0.078,0.08,0.0066,0.47,0.47,0.034,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35490000,-0.68,-0.0092,-0.0046,0.73,0.54,0.46,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00036,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,8.1e-05,0.084,0.086,0.0065,0.49,0.49,0.034,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35590000,-0.68,-0.006,-0.0046,0.73,0.43,0.37,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00033,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.8e-05,4.1e-05,7.6e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35690000,-0.68,-0.006,-0.0046,0.73,0.45,0.4,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00033,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.8e-05,4.1e-05,7.3e-05,0.072,0.074,0.0061,0.49,0.49,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35790000,-0.68,-0.0037,-0.0045,0.73,0.37,0.34,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00031,-0.075,0.052,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.3e-05,3.5e-05,6.9e-05,0.06,0.062,0.0059,0.49,0.48,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35890000,-0.68,-0.0037,-0.0046,0.73,0.39,0.37,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00031,-0.075,0.052,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,3.3e-05,3.5e-05,6.6e-05,0.066,0.067,0.0058,0.5,0.5,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +35990000,-0.68,-0.0018,-0.0045,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.0003,-0.082,0.059,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,2.9e-05,3.1e-05,6.3e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +36090000,-0.68,-0.0019,-0.0045,0.73,0.34,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.0003,-0.082,0.059,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,2.9e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-07,2.8e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +36190000,-0.68,-0.00038,-0.0044,0.73,0.28,0.28,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00029,-0.093,0.068,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.6e-05,2.7e-05,5.8e-05,0.054,0.056,0.0055,0.5,0.5,0.032,2.7e-07,2.8e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +36290000,-0.68,-0.00049,-0.0043,0.73,0.29,0.3,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00029,-0.093,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.6e-05,2.7e-05,5.6e-05,0.06,0.061,0.0056,0.52,0.52,0.032,2.7e-07,2.8e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 +36390000,-0.68,0.00062,-0.0043,0.73,0.24,0.26,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00028,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.3e-05,2.5e-05,5.4e-05,0.053,0.054,0.0055,0.51,0.51,0.032,2.8e-07,2.8e-07,9.1e-07,0.023,0.021,0.0005,0,0,0,0,0,0,0,0 +36490000,-0.68,0.00054,-0.0043,0.73,0.25,0.27,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.3e-05,2.5e-05,5.2e-05,0.058,0.06,0.0055,0.52,0.52,0.032,2.8e-07,2.8e-07,9.1e-07,0.023,0.021,0.0005,0,0,0,0,0,0,0,0 +36590000,-0.68,0.0014,-0.0042,0.73,0.21,0.24,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00027,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.1e-05,2.3e-05,5e-05,0.052,0.053,0.0055,0.52,0.52,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.021,0.0005,0,0,0,0,0,0,0,0 +36690000,-0.68,0.0014,-0.0042,0.73,0.21,0.25,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00027,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.2e-05,2.3e-05,4.9e-05,0.058,0.059,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.021,0.0005,0,0,0,0,0,0,0,0 +36790000,-0.68,0.002,-0.0041,0.73,0.18,0.22,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00026,-0.13,0.098,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,2e-05,2.1e-05,4.7e-05,0.051,0.053,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.02,0.0005,0,0,0,0,0,0,0,0 +36890000,-0.68,0.0019,-0.0041,0.73,0.18,0.23,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00026,-0.13,0.098,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,2e-05,2.1e-05,4.6e-05,0.057,0.058,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.02,0.0005,0,0,0,0,0,0,0,0 +36990000,-0.68,0.0024,-0.0039,0.73,0.15,0.2,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00026,-0.14,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,1.9e-05,2e-05,4.4e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,9.1e-07,0.021,0.02,0.0005,0,0,0,0,0,0,0,0 +37090000,-0.68,0.0023,-0.0039,0.73,0.15,0.21,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00025,-0.14,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.9e-05,2e-05,4.3e-05,0.056,0.057,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,9.1e-07,0.021,0.02,0.0005,0,0,0,0,0,0,0,0 +37190000,-0.68,0.0027,-0.0038,0.73,0.12,0.18,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00025,-0.16,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.8e-05,1.9e-05,4.2e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-07,2.9e-07,9.1e-07,0.02,0.019,0.0005,0,0,0,0,0,0,0,0 +37290000,-0.68,0.0027,-0.0039,0.74,0.12,0.18,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00024,-0.16,0.12,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.8e-05,1.9e-05,4.1e-05,0.055,0.056,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,9.1e-07,0.02,0.019,0.0005,0,0,0,0,0,0,0,0 +37390000,-0.68,0.0029,-0.0037,0.74,0.099,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00024,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.8e-05,1.9e-05,4e-05,0.049,0.05,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,9.1e-07,0.019,0.018,0.0005,0,0,0,0,0,0,0,0 +37490000,-0.68,0.0029,-0.0037,0.74,0.098,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00023,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.8e-05,1.9e-05,3.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-07,2.9e-07,9.1e-07,0.019,0.018,0.0005,0,0,0,0,0,0,0,0 +37590000,-0.68,0.003,-0.0036,0.74,0.078,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00023,-0.18,0.13,-0.094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.7e-05,1.8e-05,3.8e-05,0.048,0.049,0.0061,0.57,0.57,0.031,2.9e-07,2.9e-07,9.1e-07,0.018,0.017,0.0005,0,0,0,0,0,0,0,0 +37690000,-0.68,0.003,-0.0036,0.74,0.075,0.14,-0.11,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00023,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,1.7e-05,1.8e-05,3.7e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-07,2.9e-07,9.1e-07,0.018,0.017,0.0005,0,0,0,0,0,0,0,0 +37790000,-0.68,0.0031,-0.0036,0.74,0.058,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00022,-0.19,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,1.7e-05,1.8e-05,3.6e-05,0.047,0.048,0.0063,0.58,0.58,0.03,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 +37890000,-0.68,0.0031,-0.0036,0.74,0.055,0.13,-0.095,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00022,-0.19,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.5e-05,0.051,0.052,0.0064,0.59,0.59,0.03,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 +37990000,-0.68,0.0032,-0.0036,0.74,0.04,0.11,-0.086,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00021,-0.19,0.14,-0.096,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.4e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 +38090000,-0.68,0.0031,-0.0036,0.74,0.035,0.11,-0.076,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00021,-0.19,0.14,-0.096,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.4e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 +38190000,-0.68,0.0032,-0.0036,0.74,0.022,0.096,-0.068,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.0002,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-07,2.9e-07,9.2e-07,0.016,0.015,0.0005,0,0,0,0,0,0,0,0 +38290000,-0.68,0.0032,-0.0036,0.74,0.018,0.098,-0.061,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.0002,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.2e-05,0.049,0.049,0.0068,0.61,0.61,0.031,2.9e-07,3e-07,9.2e-07,0.016,0.015,0.0005,0,0,0,0,0,0,0,0 +38390000,-0.68,0.0032,-0.0035,0.74,0.0092,0.084,-0.053,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00019,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.2e-05,0.044,0.044,0.0069,0.61,0.61,0.031,2.9e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 +38490000,-0.68,0.0032,-0.0035,0.74,0.005,0.087,-0.046,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00019,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3.1e-05,0.047,0.048,0.007,0.62,0.62,0.031,3e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 +38590000,-0.68,0.0032,-0.0034,0.74,0.00025,0.074,-0.039,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3e-05,0.043,0.043,0.0071,0.62,0.62,0.031,3e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 +38690000,-0.68,0.0031,-0.0034,0.74,-0.005,0.074,-0.032,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 +38790000,-0.68,0.0031,-0.0034,0.74,-0.01,0.062,-0.024,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00017,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,4e-05,1.7e-05,1.8e-05,2.9e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-07,3e-07,9.2e-07,0.014,0.013,0.0005,0,0,0,0,0,0,0,0 +38890000,-0.68,0.0029,-0.0034,0.74,-0.021,0.052,0.48,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00017,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,4e-05,1.7e-05,1.8e-05,2.9e-05,0.044,0.045,0.0075,0.64,0.64,0.032,3e-07,3e-07,9.2e-07,0.014,0.013,0.0005,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 9dd222f7c1..b1b2ffde82 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -1,351 +1,351 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.8e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.8e-07,0.0025,0.0025,0.005,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -90000,0.98,-0.0095,-0.012,0.18,-5.5e-05,-0.0032,-0.024,-3.6e-06,-0.00014,-0.0021,0,0,0,0,0,0,0.2,-4.7e-10,0.43,0,0,0,0,0,9e-07,0.0026,0.0026,0.0051,25,25,10,1e+02,1e+02,1e+02,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -190000,0.98,-0.0091,-0.013,0.21,-0.0013,-0.0036,-0.037,-4.4e-05,-0.00046,-0.017,5.2e-12,-4.3e-12,-3e-14,0,0,-6.8e-10,0.2,0.012,0.43,0,0,0,0,0,2.9e-06,0.0027,0.0027,0.0052,25,25,10,1e+02,1e+02,1,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -290000,0.98,-0.0092,-0.013,0.21,-0.0016,-0.0053,-0.046,-0.00015,-0.00032,-0.018,4.4e-11,-5.5e-11,1.1e-13,0,0,-2.9e-08,0.2,0.012,0.43,0,0,0,0,0,7.1e-06,0.0029,0.0029,0.0054,25,25,9.6,0.37,0.37,0.41,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -390000,0.98,-0.0095,-0.013,0.19,-0.00033,-0.0065,-0.063,-0.00029,-0.00087,-0.013,-6.7e-11,-6.3e-11,-1.6e-12,0,0,8.8e-08,0.2,0.002,0.44,0,0,0,0,0,1.3e-05,0.0031,0.0031,0.0056,25,25,8.1,0.97,0.97,0.32,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -490000,0.98,-0.0095,-0.014,0.19,0.0016,-0.0061,-0.069,2.4e-05,-0.00049,-0.011,-1.2e-08,6.5e-09,4.2e-10,0,0,1.6e-07,0.2,0.002,0.44,0,0,0,0,0,2e-05,0.0034,0.0034,0.0058,7.8,7.8,5.9,0.34,0.34,0.31,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -590000,0.98,-0.0095,-0.014,0.19,0.0014,-0.0091,-0.12,0.00018,-0.0013,-0.029,-1.4e-08,6.7e-09,4.3e-10,0,0,6.4e-07,0.2,0.002,0.44,0,0,0,0,0,2.9e-05,0.0037,0.0037,0.0062,7.9,7.9,4.2,0.67,0.67,0.32,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -690000,0.98,-0.0096,-0.014,0.19,0.0032,-0.0083,-0.05,0.00021,-0.00076,-0.0088,-5.6e-08,1.3e-08,1.6e-09,0,0,-9.5e-07,0.2,0.002,0.44,0,0,0,0,0,4e-05,0.004,0.004,0.0065,2.7,2.7,2.8,0.26,0.26,0.29,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -790000,0.98,-0.0096,-0.014,0.19,0.0059,-0.009,-0.054,0.0006,-0.0016,-0.011,-5.5e-08,1.3e-08,1.6e-09,0,0,-1.3e-06,0.2,0.002,0.44,0,0,0,0,0,5.3e-05,0.0044,0.0044,0.0069,2.8,2.8,1.9,0.42,0.42,0.27,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -890000,0.98,-0.0096,-0.015,0.19,0.006,-0.0068,-0.093,0.00052,-0.00095,-0.031,-2.2e-07,1.6e-09,4.9e-09,0,0,-3.3e-07,0.2,0.002,0.44,0,0,0,0,0,6.7e-05,0.0048,0.0048,0.0074,1.3,1.3,1.3,0.2,0.2,0.25,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -990000,0.98,-0.0096,-0.015,0.19,0.0091,-0.0071,-0.12,0.0013,-0.0017,-0.046,-2.2e-07,1.2e-09,4.9e-09,0,0,1.3e-07,0.2,0.002,0.44,0,0,0,0,0,8.3e-05,0.0053,0.0053,0.0079,1.5,1.5,0.95,0.3,0.3,0.23,1e-06,1e-06,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1090000,0.98,-0.0096,-0.015,0.19,0.015,-0.0083,-0.13,0.0012,-0.0011,-0.062,-6.1e-07,-1.7e-07,9.8e-09,0,0,4.5e-07,0.2,0.002,0.44,0,0,0,0,0,0.0001,0.0057,0.0057,0.0084,0.92,0.92,0.69,0.17,0.17,0.2,9.8e-07,9.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1190000,0.98,-0.0096,-0.015,0.19,0.021,-0.011,-0.11,0.003,-0.0021,-0.047,-5.8e-07,-1.5e-07,9.8e-09,0,0,-4.8e-06,0.2,0.002,0.44,0,0,0,0,0,0.00012,0.0063,0.0063,0.009,1.1,1.1,0.54,0.24,0.24,0.19,9.8e-07,9.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1290000,0.98,-0.0093,-0.016,0.19,0.024,-0.0097,-0.11,0.0027,-0.0016,-0.048,-1.7e-06,-1e-06,1.5e-08,0,0,-7.5e-06,0.2,0.002,0.44,0,0,0,0,0,0.00014,0.0064,0.0064,0.0097,0.88,0.88,0.41,0.15,0.15,0.18,9.5e-07,9.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1390000,0.98,-0.0093,-0.016,0.19,0.033,-0.012,-0.097,0.0056,-0.0027,-0.038,-1.6e-06,-9.6e-07,1.5e-08,0,0,-1.4e-05,0.2,0.002,0.44,0,0,0,0,0,0.00016,0.0071,0.0071,0.01,1.1,1.1,0.33,0.21,0.21,0.16,9.5e-07,9.5e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1490000,0.98,-0.009,-0.016,0.19,0.03,-0.01,-0.12,0.0044,-0.0018,-0.053,-3.9e-06,-3.4e-06,1.2e-08,0,0,-1.2e-05,0.2,0.002,0.44,0,0,0,0,0,0.00019,0.0067,0.0067,0.011,0.95,0.95,0.27,0.14,0.14,0.15,8.9e-07,8.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1590000,0.98,-0.0091,-0.016,0.19,0.037,-0.012,-0.13,0.0077,-0.003,-0.063,-3.9e-06,-3.4e-06,1.2e-08,0,0,-1.4e-05,0.2,0.002,0.44,0,0,0,0,0,0.00022,0.0074,0.0074,0.012,1.3,1.3,0.23,0.2,0.2,0.14,8.9e-07,8.9e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1690000,0.98,-0.0088,-0.016,0.19,0.033,-0.0083,-0.13,0.0054,-0.0019,-0.068,-7.3e-06,-7.5e-06,-3.2e-09,0,0,-1.8e-05,0.2,0.002,0.44,0,0,0,0,0,0.00024,0.0064,0.0064,0.013,1,1,0.19,0.14,0.14,0.13,7.8e-07,7.8e-07,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0 -1790000,0.98,-0.009,-0.016,0.19,0.042,-0.0099,-0.13,0.0092,-0.0029,-0.067,-7.3e-06,-7.4e-06,-2.5e-09,0,0,-2.8e-05,0.2,0.002,0.44,0,0,0,0,0,0.00027,0.007,0.007,0.014,1.3,1.3,0.16,0.2,0.2,0.12,7.8e-07,7.8e-07,1e-06,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -1890000,0.98,-0.0089,-0.016,0.19,0.049,-0.0086,-0.14,0.014,-0.0037,-0.075,-7.2e-06,-7.4e-06,-2.1e-09,0,0,-3.2e-05,0.2,0.002,0.44,0,0,0,0,0,0.0003,0.0076,0.0076,0.015,1.7,1.7,0.15,0.31,0.31,0.12,7.8e-07,7.8e-07,1e-06,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -1990000,0.98,-0.0085,-0.016,0.19,0.039,-0.0042,-0.14,0.0096,-0.0021,-0.074,-1.1e-05,-1.3e-05,-3.5e-08,0,0,-4.6e-05,0.2,0.002,0.44,0,0,0,0,0,0.00034,0.0061,0.0061,0.016,1.3,1.3,0.13,0.2,0.2,0.11,6.6e-07,6.6e-07,1e-06,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -2090000,0.98,-0.0086,-0.016,0.19,0.046,-0.0041,-0.14,0.014,-0.0026,-0.071,-1.1e-05,-1.3e-05,-3.3e-08,0,0,-6.5e-05,0.2,0.002,0.44,0,0,0,0,0,0.00037,0.0066,0.0066,0.017,1.7,1.7,0.12,0.31,0.31,0.11,6.6e-07,6.6e-07,1e-06,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0 -2190000,0.98,-0.0082,-0.015,0.19,0.035,-0.0012,-0.14,0.0091,-0.0012,-0.077,-1.4e-05,-1.8e-05,-8.5e-08,0,0,-7.5e-05,0.2,0.002,0.44,0,0,0,0,0,0.00041,0.005,0.005,0.018,1.2,1.2,0.11,0.2,0.2,0.11,5.5e-07,5.5e-07,1e-06,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -2290000,0.98,-0.0082,-0.016,0.19,0.04,8.5e-05,-0.14,0.013,-0.0012,-0.075,-1.4e-05,-1.8e-05,-8.3e-08,0,0,-9.8e-05,0.2,0.002,0.44,0,0,0,0,0,0.00045,0.0054,0.0054,0.019,1.5,1.5,0.11,0.3,0.3,0.1,5.5e-07,5.5e-07,1e-06,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -2390000,0.98,-0.008,-0.015,0.19,0.031,0.0011,-0.14,0.0082,-0.00046,-0.072,-1.7e-05,-2.3e-05,-1.4e-07,0,0,-0.00012,0.2,0.002,0.44,0,0,0,0,0,0.00049,0.004,0.004,0.02,1,1,0.1,0.19,0.19,0.098,4.5e-07,4.5e-07,1e-06,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0 -2490000,0.98,-0.0079,-0.015,0.19,0.033,0.0031,-0.14,0.011,-0.00026,-0.079,-1.7e-05,-2.3e-05,-1.4e-07,0,0,-0.00013,0.2,0.002,0.44,0,0,0,0,0,0.00053,0.0044,0.0044,0.021,1.3,1.3,0.1,0.28,0.28,0.097,4.5e-07,4.5e-07,1e-06,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0 -2590000,0.98,-0.0078,-0.015,0.19,0.023,0.0022,-0.15,0.0069,8.6e-05,-0.085,-1.8e-05,-2.7e-05,-2e-07,0,0,-0.00015,0.2,0.002,0.44,0,0,0,0,0,0.00057,0.0032,0.0032,0.022,0.89,0.89,0.099,0.18,0.18,0.094,3.8e-07,3.8e-07,1e-06,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0 -2690000,0.98,-0.0078,-0.015,0.19,0.027,0.0043,-0.15,0.0095,0.00041,-0.084,-1.8e-05,-2.7e-05,-2e-07,0,0,-0.00018,0.2,0.002,0.44,0,0,0,0,0,0.00062,0.0035,0.0035,0.024,1.1,1.1,0.097,0.25,0.25,0.091,3.8e-07,3.8e-07,1e-06,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0 -2790000,0.98,-0.0077,-0.015,0.19,0.021,0.0046,-0.14,0.006,0.00052,-0.081,-1.9e-05,-3e-05,-2.5e-07,0,0,-0.00022,0.2,0.002,0.44,0,0,0,0,0,0.00066,0.0027,0.0027,0.025,0.77,0.77,0.096,0.16,0.16,0.089,3.2e-07,3.2e-07,1e-06,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0 -2890000,0.98,-0.0077,-0.015,0.19,0.025,0.0043,-0.14,0.0084,0.00092,-0.081,-1.9e-05,-3e-05,-2.5e-07,0,0,-0.00025,0.2,0.002,0.44,0,0,0,0,0,0.00071,0.0029,0.0029,0.027,0.95,0.95,0.096,0.23,0.23,0.089,3.2e-07,3.2e-07,1e-06,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0 -2990000,0.98,-0.0076,-0.015,0.19,0.019,0.0032,-0.15,0.0054,0.00069,-0.086,-2e-05,-3.3e-05,-3e-07,0,0,-0.00028,0.2,0.002,0.44,0,0,0,0,0,0.00076,0.0023,0.0023,0.028,0.67,0.67,0.095,0.15,0.15,0.088,2.7e-07,2.7e-07,1e-06,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0 -3090000,0.98,-0.0076,-0.015,0.19,0.026,0.0024,-0.15,0.0077,0.00092,-0.087,-2e-05,-3.3e-05,-2.9e-07,0,0,-0.00031,0.2,0.002,0.44,0,0,0,0,0,0.00081,0.0025,0.0025,0.03,0.82,0.82,0.095,0.22,0.22,0.086,2.7e-07,2.7e-07,1e-06,4e-06,4e-06,3.2e-06,0,0,0,0,0,0,0,0 -3190000,0.98,-0.0076,-0.015,0.19,0.021,0.001,-0.15,0.0052,0.00052,-0.097,-2e-05,-3.6e-05,-3.4e-07,0,0,-0.00033,0.2,0.002,0.44,0,0,0,0,0,0.00087,0.002,0.002,0.031,0.59,0.59,0.096,0.14,0.14,0.087,2.3e-07,2.3e-07,1e-06,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0 -3290000,0.98,-0.0075,-0.015,0.19,0.024,0.0019,-0.15,0.0075,0.00061,-0.11,-2e-05,-3.6e-05,-3.3e-07,0,0,-0.00034,0.2,0.002,0.44,0,0,0,0,0,0.00092,0.0022,0.0022,0.033,0.73,0.73,0.095,0.2,0.2,0.086,2.3e-07,2.3e-07,1e-06,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0 -3390000,0.98,-0.0073,-0.014,0.19,0.019,0.0032,-0.15,0.0051,0.00045,-0.1,-2.1e-05,-3.8e-05,-3.7e-07,0,0,-0.0004,0.2,0.002,0.44,0,0,0,0,0,0.00098,0.0017,0.0017,0.034,0.53,0.53,0.095,0.14,0.14,0.085,1.9e-07,1.9e-07,1e-06,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0 -3490000,0.98,-0.0072,-0.014,0.19,0.024,0.0064,-0.15,0.0073,0.00092,-0.1,-2.1e-05,-3.8e-05,-3.6e-07,0,0,-0.00044,0.2,0.002,0.44,0,0,0,0,0,0.001,0.0019,0.0019,0.036,0.65,0.65,0.095,0.19,0.19,0.086,1.9e-07,1.9e-07,1e-06,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0 -3590000,0.98,-0.0071,-0.014,0.19,0.021,0.0056,-0.15,0.0051,0.00081,-0.11,-2.2e-05,-4e-05,-4e-07,0,0,-0.00047,0.2,0.002,0.44,0,0,0,0,0,0.0011,0.0015,0.0015,0.038,0.48,0.48,0.094,0.13,0.13,0.086,1.6e-07,1.6e-07,1e-06,4e-06,4e-06,2.6e-06,0,0,0,0,0,0,0,0 -3690000,0.98,-0.0071,-0.014,0.19,0.023,0.0071,-0.15,0.0074,0.0014,-0.11,-2.1e-05,-4e-05,-4e-07,0,0,-0.00052,0.2,0.002,0.44,0,0,0,0,0,0.0012,0.0017,0.0017,0.04,0.59,0.59,0.093,0.18,0.18,0.085,1.6e-07,1.6e-07,1e-06,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0 -3790000,0.98,-0.007,-0.014,0.19,0.018,0.0097,-0.15,0.005,0.0012,-0.11,-2.2e-05,-4.2e-05,-4.5e-07,0,0,-0.00055,0.2,0.002,0.44,0,0,0,0,0,0.0012,0.0014,0.0014,0.042,0.44,0.44,0.093,0.12,0.12,0.086,1.4e-07,1.4e-07,1e-06,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0 -3890000,0.98,-0.007,-0.014,0.19,0.019,0.011,-0.14,0.0069,0.0023,-0.11,-2.2e-05,-4.2e-05,-4.5e-07,0,0,-0.00059,0.2,0.002,0.44,0,0,0,0,0,0.0013,0.0015,0.0015,0.043,0.54,0.54,0.091,0.17,0.17,0.086,1.4e-07,1.4e-07,1e-06,4e-06,4e-06,2.2e-06,0,0,0,0,0,0,0,0 -3990000,0.98,-0.007,-0.014,0.19,0.023,0.013,-0.14,0.0091,0.0035,-0.11,-2.2e-05,-4.2e-05,-4.4e-07,0,0,-0.00064,0.2,0.002,0.44,0,0,0,0,0,0.0014,0.0017,0.0017,0.045,0.66,0.66,0.089,0.22,0.22,0.085,1.4e-07,1.4e-07,1e-06,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0 -4090000,0.98,-0.0069,-0.014,0.19,0.02,0.011,-0.12,0.0067,0.0028,-0.098,-2.2e-05,-4.4e-05,-5e-07,0,0,-0.00072,0.2,0.002,0.44,0,0,0,0,0,0.0014,0.0013,0.0013,0.047,0.5,0.5,0.087,0.16,0.16,0.085,1.2e-07,1.2e-07,1e-06,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0 -4190000,0.98,-0.007,-0.014,0.19,0.023,0.011,-0.12,0.0088,0.0039,-0.1,-2.2e-05,-4.4e-05,-5e-07,0,0,-0.00074,0.2,0.002,0.44,0,0,0,0,0,0.0015,0.0015,0.0015,0.049,0.6,0.6,0.086,0.21,0.21,0.086,1.2e-07,1.2e-07,1e-06,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0 -4290000,0.98,-0.0071,-0.014,0.19,0.02,0.01,-0.12,0.0064,0.0029,-0.11,-2.2e-05,-4.6e-05,-5.6e-07,0,0,-0.00077,0.2,0.002,0.44,0,0,0,0,0,0.0016,0.0012,0.0012,0.052,0.46,0.46,0.084,0.15,0.15,0.085,9.6e-08,9.6e-08,1e-06,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0 -4390000,0.98,-0.0071,-0.014,0.19,0.024,0.01,-0.11,0.0087,0.0039,-0.094,-2.2e-05,-4.6e-05,-5.6e-07,0,0,-0.00083,0.2,0.002,0.44,0,0,0,0,0,0.0017,0.0013,0.0013,0.054,0.56,0.56,0.081,0.2,0.2,0.084,9.6e-08,9.6e-08,1e-06,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0 -4490000,0.98,-0.0072,-0.014,0.19,0.02,0.01,-0.11,0.0064,0.0029,-0.095,-2.1e-05,-4.8e-05,-6.1e-07,0,0,-0.00086,0.2,0.002,0.44,0,0,0,0,0,0.0017,0.0011,0.0011,0.056,0.43,0.43,0.08,0.14,0.14,0.085,7.9e-08,7.9e-08,1e-06,4e-06,4e-06,1.5e-06,0,0,0,0,0,0,0,0 -4590000,0.98,-0.0071,-0.014,0.19,0.023,0.01,-0.11,0.0085,0.0039,-0.098,-2.1e-05,-4.8e-05,-6.1e-07,0,0,-0.00089,0.2,0.002,0.44,0,0,0,0,0,0.0018,0.0011,0.0011,0.058,0.51,0.51,0.077,0.19,0.19,0.084,7.9e-08,7.9e-08,1e-06,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0 -4690000,0.98,-0.0071,-0.013,0.19,0.017,0.0083,-0.1,0.0062,0.0029,-0.09,-2.1e-05,-5e-05,-6.6e-07,0,0,-0.00093,0.2,0.002,0.44,0,0,0,0,0,0.0019,0.00093,0.00092,0.06,0.39,0.39,0.074,0.14,0.14,0.083,6.5e-08,6.5e-08,1e-06,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0 -4790000,0.98,-0.007,-0.013,0.19,0.014,0.0094,-0.099,0.0078,0.0038,-0.092,-2.1e-05,-5e-05,-6.6e-07,0,0,-0.00095,0.2,0.002,0.44,0,0,0,0,0,0.002,0.001,0.001,0.063,0.47,0.47,0.073,0.18,0.18,0.084,6.5e-08,6.5e-08,1e-06,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0 -4890000,0.98,-0.007,-0.013,0.19,0.01,0.0054,-0.093,0.0052,0.0026,-0.088,-2.1e-05,-5.1e-05,-7.1e-07,0,0,-0.00099,0.2,0.002,0.44,0,0,0,0,0,0.0021,0.00081,0.00081,0.065,0.36,0.36,0.07,0.13,0.13,0.083,5.3e-08,5.3e-08,1e-06,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0 -4990000,0.98,-0.0069,-0.013,0.19,0.014,0.0072,-0.085,0.0064,0.0033,-0.083,-2.1e-05,-5.1e-05,-7.1e-07,0,0,-0.001,0.2,0.002,0.44,0,0,0,0,0,0.0021,0.00088,0.00087,0.068,0.43,0.43,0.067,0.17,0.17,0.082,5.3e-08,5.3e-08,1e-06,4e-06,4e-06,1e-06,0,0,0,0,0,0,0,0 -5090000,0.98,-0.0069,-0.013,0.19,0.01,0.0064,-0.082,0.0045,0.0023,-0.081,-2.1e-05,-5.2e-05,-7.4e-07,0,0,-0.001,0.2,0.002,0.44,0,0,0,0,0,0.0022,0.00071,0.0007,0.07,0.33,0.33,0.065,0.12,0.12,0.082,4.3e-08,4.3e-08,1e-06,4e-06,4e-06,9.8e-07,0,0,0,0,0,0,0,0 -5190000,0.98,-0.0067,-0.013,0.19,0.0089,0.0096,-0.08,0.0054,0.0031,-0.079,-2.1e-05,-5.2e-05,-7.4e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,0.0023,0.00076,0.00075,0.073,0.39,0.39,0.063,0.16,0.16,0.081,4.3e-08,4.3e-08,1e-06,4e-06,4e-06,9.1e-07,0,0,0,0,0,0,0,0 -5290000,0.98,-0.0066,-0.013,0.19,0.0071,0.0092,-0.068,0.0037,0.0024,-0.072,-2.1e-05,-5.3e-05,-7.7e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,0.0024,0.00061,0.00061,0.075,0.3,0.3,0.06,0.12,0.12,0.08,3.5e-08,3.5e-08,1e-06,4e-06,4e-06,8.4e-07,0,0,0,0,0,0,0,0 -5390000,0.98,-0.0065,-0.013,0.19,0.0055,0.012,-0.065,0.0044,0.0034,-0.067,-2.1e-05,-5.3e-05,-7.7e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,0.0025,0.00066,0.00065,0.078,0.36,0.36,0.057,0.15,0.15,0.079,3.5e-08,3.5e-08,1e-06,4e-06,4e-06,7.8e-07,0,0,0,0,0,0,0,0 -5490000,0.98,-0.0066,-0.013,0.19,0.0043,0.013,-0.06,0.0028,0.0028,-0.065,-2.1e-05,-5.4e-05,-8.1e-07,0,0,-0.0011,0.2,0.002,0.44,0,0,0,0,0,0.0026,0.00053,0.00053,0.08,0.28,0.28,0.056,0.11,0.11,0.079,2.8e-08,2.8e-08,1e-06,4e-06,4e-06,7.3e-07,0,0,0,0,0,0,0,0 -5590000,0.98,-0.0066,-0.013,0.19,0.0043,0.017,-0.053,0.0033,0.0044,-0.058,-2.1e-05,-5.4e-05,-8.1e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0027,0.00057,0.00056,0.083,0.32,0.32,0.053,0.15,0.15,0.078,2.8e-08,2.8e-08,1e-06,4e-06,4e-06,6.7e-07,0,0,0,0,0,0,0,0 -5690000,0.98,-0.0067,-0.013,0.19,0.0034,0.017,-0.052,0.0022,0.0036,-0.055,-2e-05,-5.4e-05,-8.7e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0028,0.00046,0.00045,0.086,0.25,0.25,0.051,0.11,0.11,0.076,2.3e-08,2.3e-08,1e-06,4e-06,4e-06,6.2e-07,0,0,0,0,0,0,0,0 -5790000,0.98,-0.0065,-0.013,0.19,0.004,0.02,-0.049,0.0026,0.0054,-0.053,-2e-05,-5.4e-05,-8.7e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0029,0.00049,0.00049,0.089,0.29,0.29,0.05,0.14,0.14,0.077,2.3e-08,2.3e-08,1e-06,4e-06,4e-06,5.8e-07,0,0,0,0,0,0,0,0 -5890000,0.98,-0.0066,-0.013,0.19,0.005,0.018,-0.048,0.0018,0.0044,-0.056,-1.9e-05,-5.5e-05,-9.5e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.003,0.0004,0.00039,0.092,0.23,0.23,0.048,0.1,0.1,0.075,1.9e-08,1.9e-08,1e-06,4e-06,4e-06,5.4e-07,0,0,0,0,0,0,0,0 -5990000,0.98,-0.0065,-0.013,0.19,0.0061,0.019,-0.041,0.0024,0.0062,-0.05,-1.9e-05,-5.5e-05,-9.5e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0031,0.00043,0.00042,0.095,0.27,0.27,0.045,0.13,0.13,0.074,1.9e-08,1.9e-08,1e-06,4e-06,4e-06,5e-07,0,0,0,0,0,0,0,0 -6090000,0.98,-0.0065,-0.013,0.19,0.0058,0.021,-0.039,0.003,0.0082,-0.047,-1.9e-05,-5.5e-05,-9.5e-07,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0032,0.00046,0.00045,0.098,0.31,0.31,0.044,0.17,0.17,0.074,1.9e-08,1.9e-08,1e-06,4e-06,4e-06,4.7e-07,0,0,0,0,0,0,0,0 -6190000,0.98,-0.0066,-0.013,0.19,0.0037,0.019,-0.037,0.0022,0.0066,-0.047,-1.9e-05,-5.6e-05,-1e-06,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0033,0.00037,0.00036,0.1,0.24,0.24,0.042,0.13,0.13,0.073,1.5e-08,1.5e-08,1e-06,4e-06,4e-06,4.4e-07,0,0,0,0,0,0,0,0 -6290000,0.98,-0.0066,-0.013,0.19,0.0022,0.021,-0.041,0.0025,0.0085,-0.053,-1.9e-05,-5.6e-05,-1e-06,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.0034,0.00039,0.00039,0.1,0.28,0.28,0.04,0.16,0.16,0.072,1.5e-08,1.5e-08,1e-06,4e-06,4e-06,4.1e-07,0,0,0,0,0,0,0,0 -6390000,0.98,-0.0067,-0.013,0.19,0.0032,0.018,-0.042,0.0017,0.0068,-0.056,-1.8e-05,-5.6e-05,-1.5e-06,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.0003,0.0003,0.0035,0.2,0.2,0.039,0.12,0.12,0.072,1.2e-08,1.2e-08,1e-06,4e-06,4e-06,3.8e-07,0,0,0,0,0,0,0,0 -6490000,0.98,-0.0066,-0.013,0.19,0.00096,0.017,-0.039,0.0019,0.0085,-0.053,-1.8e-05,-5.6e-05,-5.4e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.0003,0.0003,0.0015,0.21,0.21,0.038,0.15,0.15,0.07,1.2e-08,1.2e-08,9.9e-07,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0 -6590000,0.98,-0.0065,-0.013,0.19,0.00025,0.02,-0.042,0.002,0.01,-0.056,-1.8e-05,-5.6e-05,-9.6e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.0003,0.0003,0.001,0.21,0.21,0.036,0.18,0.18,0.069,1.2e-08,1.2e-08,9.8e-07,4e-06,4e-06,3.3e-07,0,0,0,0,0,0,0,0 -6690000,0.98,-0.0064,-0.013,0.19,-0.0024,0.022,-0.044,0.0018,0.012,-0.057,-1.9e-05,-5.6e-05,-1.7e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0003,0.0003,0.0008,0.22,0.22,0.035,0.22,0.22,0.068,1.2e-08,1.2e-08,9.6e-07,4e-06,4e-06,3.1e-07,0,0,0,0,0,0,0,0 -6790000,0.98,-0.0064,-0.013,0.19,-0.00065,0.024,-0.042,0.0016,0.015,-0.058,-1.9e-05,-5.6e-05,-2.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0003,0.0003,0.00071,0.23,0.24,0.034,0.26,0.26,0.068,1.2e-08,1.2e-08,9.2e-07,4e-06,4e-06,2.9e-07,0,0,0,0,0,0,0,0 -6890000,0.98,-0.0062,-0.013,0.19,-0.0011,0.024,-0.038,0.0016,0.017,-0.055,-1.9e-05,-5.6e-05,-2.3e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00066,0.25,0.25,0.032,0.31,0.31,0.067,1.2e-08,1.2e-08,8.7e-07,4e-06,4e-06,2.7e-07,0,0,0,0,0,0,0,0 -6990000,0.98,-0.0062,-0.013,0.19,-0.0011,0.026,-0.037,0.0014,0.019,-0.055,-1.9e-05,-5.6e-05,-2.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00063,0.27,0.27,0.031,0.36,0.36,0.066,1.2e-08,1.2e-08,8.1e-07,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0 -7090000,0.98,-0.0061,-0.012,0.19,-0.002,0.031,-0.037,0.0013,0.022,-0.056,-1.9e-05,-5.6e-05,-1.9e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00064,0.29,0.29,0.03,0.42,0.42,0.066,1.2e-08,1.2e-08,7.5e-07,4e-06,4e-06,2.4e-07,0,0,0,0,0,0,0,0 -7190000,0.98,-0.006,-0.013,0.19,-0.0025,0.034,-0.036,0.00097,0.026,-0.058,-1.9e-05,-5.5e-05,-2.5e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00032,0.00032,0.00063,0.32,0.32,0.029,0.49,0.49,0.065,1.2e-08,1.2e-08,6.7e-07,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0 -7290000,0.98,-0.006,-0.013,0.19,-0.0017,0.038,-0.034,0.00073,0.029,-0.054,-1.9e-05,-5.6e-05,-2.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00032,0.00032,0.00063,0.35,0.35,0.028,0.56,0.56,0.064,1.2e-08,1.2e-08,5.9e-07,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0 -7390000,0.98,-0.0058,-0.013,0.19,-0.0034,0.041,-0.032,0.00052,0.033,-0.052,-1.9e-05,-5.6e-05,-1.6e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00033,0.00033,0.00064,0.38,0.38,0.027,0.64,0.64,0.064,1.2e-08,1.2e-08,5.3e-07,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0 -7490000,0.98,-0.0058,-0.013,0.19,-0.0011,0.045,-0.026,0.00041,0.038,-0.046,-1.8e-05,-5.6e-05,-2.8e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.00063,0.42,0.42,0.026,0.73,0.73,0.063,1.2e-08,1.2e-08,4.6e-07,4e-06,4e-06,1.9e-07,0,0,0,0,0,0,0,0 -7590000,0.98,-0.0059,-0.013,0.19,-9.4e-05,0.048,-0.023,0.00036,0.042,-0.041,-1.8e-05,-5.6e-05,-9.7e-07,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.00061,0.45,0.45,0.025,0.83,0.83,0.062,1.2e-08,1.2e-08,4e-07,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0 -7690000,0.98,-0.0059,-0.013,0.19,-0.00044,0.052,-0.022,0.00033,0.047,-0.036,-1.8e-05,-5.6e-05,-2.8e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.00061,0.5,0.5,0.025,0.95,0.95,0.062,1.2e-08,1.2e-08,3.5e-07,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0 -7790000,0.98,-0.0058,-0.013,0.19,0.0012,0.054,-0.024,0.00034,0.052,-0.041,-1.8e-05,-5.6e-05,-7e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.00059,0.54,0.54,0.024,1.1,1.1,0.061,1.2e-08,1.2e-08,3e-07,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.00018,0.059,-0.025,0.00029,0.057,-0.045,-1.8e-05,-5.6e-05,-8.5e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.00057,0.59,0.59,0.023,1.2,1.2,0.06,1.2e-08,1.2e-08,2.6e-07,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0 -7990000,0.98,-0.0057,-0.013,0.19,7.7e-05,0.062,-0.021,0.0003,0.062,-0.041,-1.8e-05,-5.6e-05,-6.7e-06,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.00055,0.64,0.64,0.022,1.4,1.4,0.059,1.2e-08,1.2e-08,2.2e-07,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.0016,0.067,-0.022,0.00037,0.069,-0.044,-1.8e-05,-5.6e-05,-1.7e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00038,0.00038,0.00054,0.7,0.7,0.022,1.5,1.5,0.059,1.2e-08,1.2e-08,2e-07,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0 -8190000,0.98,-0.0056,-0.013,0.19,0.0022,0.073,-0.018,0.00053,0.076,-0.038,-1.9e-05,-5.6e-05,-2.2e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00039,0.00039,0.00052,0.76,0.76,0.021,1.7,1.7,0.058,1.2e-08,1.2e-08,1.7e-07,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0 -8290000,0.98,-0.0056,-0.013,0.19,0.0044,0.077,-0.016,0.00085,0.082,-0.038,-1.8e-05,-5.6e-05,-2.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0004,0.0004,0.0005,0.81,0.81,0.02,1.9,1.9,0.057,1.2e-08,1.2e-08,1.5e-07,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.0022,0.08,-0.015,0.0012,0.09,-0.036,-1.8e-05,-5.6e-05,-2.1e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00041,0.00041,0.00049,0.88,0.88,0.02,2.2,2.2,0.057,1.2e-08,1.2e-08,1.3e-07,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0 -8490000,0.98,-0.0055,-0.013,0.19,0.002,0.084,-0.017,0.0014,0.096,-0.041,-1.8e-05,-5.6e-05,-1.4e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00042,0.00042,0.00047,0.94,0.94,0.019,2.4,2.4,0.056,1.1e-08,1.1e-08,1.2e-07,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0 -8590000,0.98,-0.0054,-0.013,0.19,0.0031,0.088,-0.012,0.0016,0.1,-0.036,-1.8e-05,-5.6e-05,-1.5e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00043,0.00043,0.00045,1,1,0.018,2.7,2.7,0.055,1.1e-08,1.1e-08,1e-07,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0 -8690000,0.98,-0.0055,-0.013,0.19,0.003,0.089,-0.014,0.0019,0.11,-0.037,-1.8e-05,-5.6e-05,-1.3e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00043,0.00043,0.00045,1.1,1.1,0.018,2.9,2.9,0.055,1.1e-08,1.1e-08,9.4e-08,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0 -8790000,0.98,-0.0054,-0.013,0.19,0.0045,0.093,-0.013,0.0021,0.12,-0.035,-1.8e-05,-5.6e-05,-1.6e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00045,0.00045,0.00043,1.2,1.2,0.018,3.3,3.3,0.055,1.1e-08,1.1e-08,8.4e-08,4e-06,4e-06,9.6e-08,0,0,0,0,0,0,0,0 -8890000,0.98,-0.0055,-0.013,0.19,0.0045,0.095,-0.0091,0.0025,0.13,-0.029,-1.8e-05,-5.6e-05,-1.1e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00045,0.00045,0.00041,1.2,1.2,0.017,3.6,3.6,0.054,1.1e-08,1.1e-08,7.5e-08,4e-06,4e-06,9.1e-08,0,0,0,0,0,0,0,0 -8990000,0.98,-0.0054,-0.013,0.19,0.0035,0.1,-0.0083,0.0029,0.14,-0.032,-1.8e-05,-5.6e-05,-5.9e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.00041,1.3,1.3,0.017,4,4,0.054,1.1e-08,1.1e-08,6.8e-08,4e-06,4e-06,8.8e-08,0,0,0,0,0,0,0,0 -9090000,0.98,-0.0055,-0.013,0.19,0.0038,0.1,-0.0093,0.0032,0.14,-0.032,-1.7e-05,-5.6e-05,-8.8e-07,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.00039,1.3,1.3,0.016,4.2,4.2,0.053,1.1e-08,1.1e-08,6.1e-08,4e-06,4e-06,8.4e-08,0,0,0,0,0,0,0,0 -9190000,0.98,-0.0054,-0.013,0.19,0.0073,0.11,-0.0088,0.0037,0.15,-0.032,-1.7e-05,-5.6e-05,2.7e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00038,1.4,1.4,0.016,4.7,4.7,0.052,1.1e-08,1.1e-08,5.5e-08,4e-06,4e-06,8e-08,0,0,0,0,0,0,0,0 -9290000,0.98,-0.0053,-0.013,0.19,0.0095,0.11,-0.0072,0.0044,0.15,-0.03,-1.7e-05,-5.6e-05,3.6e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00037,1.5,1.5,0.015,5,5,0.052,1.1e-08,1.1e-08,5e-08,4e-06,4e-06,7.6e-08,0,0,0,0,0,0,0,0 -9390000,0.98,-0.0052,-0.013,0.19,0.0097,0.11,-0.0061,0.0055,0.16,-0.03,-1.7e-05,-5.6e-05,-2.2e-08,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00048,0.00048,0.00036,1.6,1.6,0.015,5.5,5.5,0.052,1.1e-08,1.1e-08,4.6e-08,4e-06,4e-06,7.3e-08,0,0,0,0,0,0,0,0 -9490000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0044,0.0061,0.17,-0.027,-1.7e-05,-5.7e-05,1.2e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00035,1.6,1.6,0.015,5.8,5.8,0.051,1e-08,1e-08,4.2e-08,4e-06,4e-06,7e-08,0,0,0,0,0,0,0,0 -9590000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0043,0.0069,0.18,-0.028,-1.7e-05,-5.6e-05,-4.5e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00034,1.7,1.7,0.014,6.4,6.4,0.05,1e-08,1e-08,3.8e-08,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0 -9690000,0.98,-0.0054,-0.013,0.19,0.0091,0.11,-0.0014,0.0074,0.18,-0.027,-1.7e-05,-5.6e-05,-5.6e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00033,1.7,1.7,0.014,6.6,6.6,0.05,9.9e-09,1e-08,3.5e-08,4e-06,4e-06,6.5e-08,0,0,0,0,0,0,0,0 -9790000,0.98,-0.0054,-0.013,0.19,0.011,0.11,-0.0027,0.0084,0.19,-0.028,-1.7e-05,-5.6e-05,-1e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00032,1.8,1.8,0.014,7.3,7.3,0.05,9.9e-09,1e-08,3.2e-08,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0 -9890000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0014,0.0088,0.18,-0.029,-1.7e-05,-5.7e-05,-8.4e-06,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00031,1.8,1.8,0.013,7.4,7.4,0.049,9.6e-09,9.7e-09,3e-08,4e-06,4e-06,6e-08,0,0,0,0,0,0,0,0 -9990000,0.98,-0.0054,-0.013,0.19,0.014,0.11,-0.00073,0.01,0.2,-0.031,-1.7e-05,-5.7e-05,-1.1e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00031,1.9,1.9,0.013,8.2,8.2,0.049,9.6e-09,9.7e-09,2.7e-08,4e-06,4e-06,5.8e-08,0,0,0,0,0,0,0,0 -10090000,0.98,-0.0055,-0.013,0.19,0.012,0.11,0.00048,0.011,0.19,-0.029,-1.6e-05,-5.7e-05,-1.4e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.0003,1.9,1.9,0.013,8.2,8.2,0.048,9.3e-09,9.3e-09,2.5e-08,4e-06,4e-06,5.6e-08,0,0,0,0,0,0,0,0 -10190000,0.98,-0.0054,-0.013,0.19,0.011,0.11,0.0014,0.012,0.2,-0.03,-1.6e-05,-5.7e-05,-1.7e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00048,0.00048,0.00029,2,2,0.012,9,9,0.048,9.3e-09,9.3e-09,2.3e-08,4e-06,4e-06,5.4e-08,0,0,0,0,0,0,0,0 -10290000,0.98,-0.0055,-0.013,0.19,0.011,0.11,0.00029,0.013,0.21,-0.029,-1.6e-05,-5.7e-05,-1.5e-05,0,0,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00028,2.1,2.1,0.012,9.9,9.9,0.048,9.3e-09,9.3e-09,2.2e-08,4e-06,4e-06,5.2e-08,0,0,0,0,0,0,0,0 -10390000,0.98,-0.0055,-0.013,0.19,0.007,0.0051,-0.0025,0.00075,0.00014,-0.028,-1.6e-05,-5.7e-05,-1.3e-05,-3.6e-10,2.5e-10,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00051,0.00051,0.00028,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-09,9.3e-09,2e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10490000,0.98,-0.0054,-0.012,0.19,0.0083,0.0074,0.007,0.0015,0.00073,-0.023,-1.6e-05,-5.7e-05,-1.5e-05,-1.2e-08,8.4e-09,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00027,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-09,9.3e-09,1.9e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10590000,0.98,-0.0053,-0.012,0.19,-0.0013,0.0053,0.013,-0.0012,-0.0054,-0.021,-1.6e-05,-5.7e-05,-1.2e-05,3.2e-06,5.4e-08,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00026,0.13,0.13,0.27,0.13,0.13,0.055,9.3e-09,9.3e-09,1.7e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10690000,0.98,-0.0053,-0.012,0.19,-0.00024,0.0064,0.016,-0.0013,-0.0049,-0.017,-1.6e-05,-5.7e-05,-1.3e-05,3.2e-06,6.1e-08,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00055,0.00055,0.00026,0.14,0.14,0.26,0.14,0.14,0.065,9.3e-09,9.3e-09,1.6e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10790000,0.98,-0.0054,-0.012,0.19,0.0016,0.0029,0.014,-0.00078,-0.0047,-0.015,-1.6e-05,-5.7e-05,-1.2e-05,5.2e-06,4.7e-06,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00054,0.00054,0.00025,0.1,0.1,0.17,0.091,0.091,0.062,9e-09,9e-09,1.5e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10890000,0.98,-0.0053,-0.013,0.19,0.0016,0.0063,0.01,-0.00062,-0.0043,-0.018,-1.6e-05,-5.7e-05,-8.8e-06,5.2e-06,4.7e-06,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00056,0.00056,0.00025,0.12,0.12,0.16,0.098,0.098,0.068,9e-09,9e-09,1.4e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -10990000,0.98,-0.0054,-0.013,0.19,0.0011,0.012,0.016,-0.00046,-0.003,-0.011,-1.6e-05,-5.7e-05,-9.1e-06,6.6e-06,7.1e-06,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00024,0.092,0.092,0.12,0.073,0.073,0.065,8.6e-09,8.6e-09,1.4e-08,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0 -11090000,0.98,-0.0055,-0.013,0.19,0.0021,0.017,0.02,-0.00034,-0.0016,-0.0074,-1.6e-05,-5.7e-05,-1.1e-05,6.6e-06,7.1e-06,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00054,0.00054,0.00024,0.11,0.11,0.11,0.08,0.08,0.069,8.6e-09,8.6e-09,1.3e-08,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0 -11190000,0.98,-0.0058,-0.013,0.19,0.0037,0.017,0.026,0.001,-0.0018,-0.00035,-1.5e-05,-5.7e-05,-1.2e-05,6.3e-06,1.6e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00049,0.00049,0.00023,0.092,0.092,0.083,0.063,0.063,0.066,8e-09,8e-09,1.2e-08,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0 -11290000,0.98,-0.0058,-0.013,0.19,0.0039,0.018,0.026,0.0014,2.5e-05,-0.00012,-1.5e-05,-5.7e-05,-1.2e-05,6.4e-06,1.6e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00051,0.00051,0.00023,0.11,0.11,0.077,0.07,0.07,0.069,8e-09,8e-09,1.1e-08,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0 -11390000,0.98,-0.0059,-0.013,0.19,0.0023,0.016,0.016,0.00086,-0.00079,-0.0086,-1.4e-05,-5.8e-05,-1.1e-05,1.2e-05,2.3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00044,0.00044,0.00023,0.093,0.093,0.062,0.057,0.057,0.066,7.4e-09,7.4e-09,1.1e-08,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11490000,0.98,-0.0058,-0.013,0.19,0.0013,0.017,0.02,0.00098,0.00085,-0.0025,-1.4e-05,-5.8e-05,-1e-05,1.2e-05,2.3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00046,0.00046,0.00022,0.11,0.11,0.057,0.065,0.065,0.067,7.4e-09,7.4e-09,1e-08,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11590000,0.98,-0.0062,-0.012,0.19,0.0032,0.013,0.018,0.00082,-0.00023,-0.0036,-1.4e-05,-5.8e-05,-9.7e-06,1.5e-05,3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00039,0.00039,0.00022,0.092,0.092,0.048,0.054,0.054,0.065,6.7e-09,6.7e-09,9.5e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11690000,0.98,-0.0061,-0.012,0.19,0.0036,0.017,0.018,0.0012,0.0013,-0.0049,-1.4e-05,-5.8e-05,-8.7e-06,1.5e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0004,0.0004,0.00021,0.11,0.11,0.044,0.062,0.062,0.066,6.7e-09,6.7e-09,9e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0 -11790000,0.98,-0.0065,-0.012,0.19,0.0023,0.011,0.019,0.00068,-0.0016,-0.002,-1.3e-05,-5.9e-05,-6.3e-06,2.1e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00034,0.00034,0.00021,0.09,0.09,0.037,0.052,0.052,0.063,6.2e-09,6.2e-09,8.5e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -11890000,0.98,-0.0066,-0.012,0.19,0.005,0.013,0.017,0.001,-0.00042,-0.0013,-1.3e-05,-5.9e-05,-6.3e-06,2.1e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00035,0.00035,0.00021,0.11,0.11,0.034,0.06,0.06,0.063,6.2e-09,6.2e-09,8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -11990000,0.98,-0.0068,-0.012,0.19,0.0079,0.013,0.015,0.0021,-0.0016,-0.0049,-1.2e-05,-5.9e-05,-5.4e-06,2.1e-05,4.1e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0003,0.0003,0.0002,0.086,0.086,0.03,0.051,0.051,0.061,5.7e-09,5.7e-09,7.6e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12090000,0.98,-0.0067,-0.012,0.19,0.0095,0.013,0.018,0.003,-0.00037,0.0011,-1.2e-05,-5.9e-05,-5.1e-06,2e-05,4.1e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00031,0.00031,0.0002,0.1,0.1,0.027,0.059,0.059,0.06,5.7e-09,5.7e-09,7.2e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12190000,0.98,-0.0066,-0.012,0.19,0.0077,0.012,0.017,0.0018,0.00055,0.0029,-1.2e-05,-5.9e-05,-5.4e-06,2.3e-05,4e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00027,0.00027,0.0002,0.081,0.081,0.024,0.05,0.05,0.058,5.3e-09,5.3e-09,6.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12290000,0.98,-0.0067,-0.012,0.19,0.0054,0.011,0.016,0.0025,0.0017,0.0039,-1.2e-05,-5.9e-05,-5.6e-06,2.3e-05,4e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00028,0.00028,0.00019,0.096,0.096,0.022,0.059,0.059,0.058,5.3e-09,5.3e-09,6.6e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0 -12390000,0.98,-0.0068,-0.012,0.19,0.004,0.0078,0.014,0.0017,0.00065,-0.0021,-1.2e-05,-5.9e-05,-5.3e-06,2.6e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00025,0.00025,0.00019,0.076,0.076,0.02,0.05,0.05,0.056,4.9e-09,4.9e-09,6.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -12490000,0.98,-0.0068,-0.012,0.19,0.004,0.0089,0.018,0.0021,0.0015,-6.6e-05,-1.2e-05,-5.9e-05,-5.1e-06,2.6e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00026,0.00026,0.00019,0.089,0.089,0.018,0.058,0.058,0.055,4.9e-09,4.9e-09,5.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -12590000,0.98,-0.007,-0.012,0.19,0.0078,0.0022,0.02,0.0033,-0.0012,0.0017,-1.2e-05,-5.9e-05,-4.9e-06,2.6e-05,4.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00023,0.00023,0.00018,0.071,0.071,0.017,0.049,0.049,0.054,4.7e-09,4.7e-09,5.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -12690000,0.98,-0.007,-0.012,0.19,0.0083,0.0001,0.019,0.004,-0.0011,0.0033,-1.2e-05,-5.9e-05,-4.6e-06,2.6e-05,4.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00024,0.00024,0.00018,0.083,0.083,0.016,0.058,0.058,0.053,4.7e-09,4.7e-09,5.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -12790000,0.98,-0.0072,-0.012,0.19,0.0099,-0.0034,0.021,0.0041,-0.0042,0.0054,-1.1e-05,-5.9e-05,-2.6e-06,2.7e-05,4.7e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00022,0.00022,0.00018,0.067,0.067,0.014,0.049,0.049,0.052,4.4e-09,4.4e-09,5.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -12890000,0.98,-0.0072,-0.012,0.19,0.01,-0.0042,0.022,0.0051,-0.0046,0.0085,-1.1e-05,-5.9e-05,-1.3e-06,2.7e-05,4.7e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00023,0.00023,0.00018,0.077,0.077,0.013,0.058,0.058,0.051,4.4e-09,4.4e-09,4.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -12990000,0.98,-0.0072,-0.012,0.19,0.008,-0.0023,0.022,0.0036,-0.0034,0.0096,-1.1e-05,-6e-05,-1.1e-07,2.8e-05,4.6e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.063,0.063,0.012,0.049,0.049,0.05,4.2e-09,4.2e-09,4.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13090000,0.98,-0.0072,-0.012,0.19,0.0089,-0.0022,0.02,0.0044,-0.0036,0.0085,-1.1e-05,-6e-05,1.3e-06,2.8e-05,4.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00022,0.00022,0.00017,0.072,0.072,0.012,0.057,0.057,0.049,4.2e-09,4.2e-09,4.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13190000,0.98,-0.0072,-0.012,0.19,0.0039,-0.0039,0.019,0.00095,-0.0044,0.0091,-1.1e-05,-6e-05,2.2e-06,2.9e-05,4.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.059,0.059,0.011,0.049,0.049,0.047,4e-09,4e-09,4.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0048,0.016,0.0013,-0.0048,0.0085,-1.1e-05,-6e-05,2.4e-06,2.9e-05,4.4e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.067,0.067,0.01,0.057,0.057,0.047,4e-09,4e-09,4.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13390000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0029,0.016,0.00084,-0.0036,0.0091,-1.1e-05,-6e-05,2e-06,3e-05,4.4e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.056,0.056,0.0097,0.049,0.049,0.046,3.8e-09,3.8e-09,4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13490000,0.98,-0.0072,-0.012,0.19,0.0031,-0.0012,0.015,0.0011,-0.0038,0.0053,-1.1e-05,-6e-05,2.4e-06,3.1e-05,4.3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00016,0.063,0.063,0.0093,0.056,0.056,0.045,3.8e-09,3.8e-09,3.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0015,0.017,0.004,-0.0031,0.0038,-1.1e-05,-6e-05,2.2e-06,3.2e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.053,0.053,0.0088,0.048,0.048,0.044,3.6e-09,3.6e-09,3.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13690000,0.98,-0.0071,-0.012,0.19,0.0076,-0.0029,0.017,0.0047,-0.0033,0.0064,-1.1e-05,-6e-05,2.9e-06,3.2e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.06,0.06,0.0085,0.056,0.056,0.044,3.6e-09,3.6e-09,3.5e-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.0012,0.017,0.0083,-0.00086,0.0059,-1.1e-05,-5.9e-05,2.6e-06,3.6e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.05,0.05,0.0082,0.048,0.048,0.043,3.5e-09,3.5e-09,3.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13890000,0.98,-0.007,-0.012,0.19,0.016,0.0019,0.018,0.0098,-0.00069,0.0081,-1.1e-05,-5.9e-05,3.4e-06,3.6e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.057,0.057,0.008,0.056,0.056,0.042,3.5e-09,3.5e-09,3.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -13990000,0.98,-0.007,-0.012,0.19,0.015,0.002,0.017,0.0073,-0.0022,0.007,-1.1e-05,-6e-05,4.2e-06,3.4e-05,4e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00015,0.048,0.048,0.0077,0.048,0.048,0.041,3.3e-09,3.3e-09,3.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0024,0.018,0.0088,-0.0023,0.0034,-1.1e-05,-5.9e-05,2.6e-06,3.5e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.055,0.055,0.0076,0.055,0.055,0.041,3.3e-09,3.3e-09,3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14190000,0.98,-0.007,-0.012,0.19,0.01,-0.0012,0.018,0.008,-0.0017,0.0036,-1.1e-05,-6e-05,1.9e-06,3.6e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00015,0.046,0.046,0.0074,0.048,0.048,0.04,3.1e-09,3.1e-09,2.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0012,0.016,0.009,-0.0018,0.0079,-1.1e-05,-6e-05,2e-06,3.6e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.052,0.052,0.0073,0.055,0.055,0.04,3.1e-09,3.1e-09,2.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0042,0.017,0.0084,-0.003,0.012,-1.1e-05,-6e-05,2.5e-06,3.5e-05,3.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.045,0.045,0.0071,0.048,0.048,0.039,3e-09,3e-09,2.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.0039,0.021,0.0095,-0.0034,0.015,-1.1e-05,-6e-05,1.8e-06,3.4e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00014,0.051,0.051,0.0071,0.055,0.055,0.038,3e-09,3e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14590000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0041,0.019,0.0059,-0.0041,0.011,-1.1e-05,-6e-05,1.7e-06,3.2e-05,3.7e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.044,0.044,0.007,0.047,0.047,0.038,2.8e-09,2.8e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14690000,0.98,-0.0072,-0.011,0.19,0.0073,-0.0041,0.019,0.0067,-0.0045,0.011,-1.1e-05,-6e-05,2e-06,3.3e-05,3.7e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.049,0.049,0.007,0.054,0.054,0.037,2.8e-09,2.8e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14790000,0.98,-0.0072,-0.011,0.19,0.009,0.0028,0.019,0.0053,0.00086,0.014,-1.2e-05,-6e-05,2.9e-06,3.3e-05,4.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.042,0.042,0.0069,0.047,0.047,0.037,2.6e-09,2.6e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14890000,0.98,-0.0071,-0.011,0.19,0.0077,0.00045,0.023,0.0061,0.001,0.014,-1.2e-05,-6e-05,3.5e-06,3.4e-05,4.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.048,0.048,0.007,0.054,0.054,0.037,2.6e-09,2.6e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -14990000,0.98,-0.0072,-0.011,0.19,0.0064,-0.0012,0.026,0.0048,-0.00061,0.017,-1.2e-05,-6e-05,3.9e-06,3.2e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.042,0.042,0.0069,0.047,0.047,0.036,2.5e-09,2.5e-09,2.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15090000,0.98,-0.0072,-0.011,0.19,0.0065,-0.00011,0.03,0.0054,-0.00072,0.019,-1.2e-05,-6e-05,3.8e-06,3.2e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.047,0.047,0.007,0.054,0.054,0.036,2.5e-09,2.5e-09,2.1e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15190000,0.98,-0.0073,-0.011,0.19,0.0046,-0.0012,0.03,0.0042,-0.00067,0.021,-1.2e-05,-6.1e-05,3.6e-06,3.2e-05,4.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.041,0.041,0.007,0.047,0.047,0.036,2.3e-09,2.3e-09,2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15290000,0.98,-0.0074,-0.011,0.19,0.0052,-0.0023,0.03,0.0048,-0.00083,0.018,-1.2e-05,-6.1e-05,4.2e-06,3.4e-05,4e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.046,0.046,0.0071,0.054,0.054,0.035,2.3e-09,2.3e-09,2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15390000,0.98,-0.0075,-0.011,0.19,0.0054,8.3e-05,0.029,0.0038,-0.00056,0.018,-1.2e-05,-6.1e-05,4.1e-06,3.5e-05,3.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.04,0.04,0.007,0.047,0.047,0.035,2.1e-09,2.1e-09,1.9e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15490000,0.98,-0.0075,-0.011,0.19,0.0048,-0.0024,0.029,0.0043,-0.00065,0.019,-1.2e-05,-6.1e-05,4.1e-06,3.6e-05,3.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.045,0.045,0.0072,0.053,0.053,0.035,2.1e-09,2.1e-09,1.8e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.0063,0.029,0.0063,-0.0046,0.018,-1.1e-05,-6.1e-05,4.5e-06,3.9e-05,2.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.04,0.04,0.0072,0.046,0.046,0.035,2e-09,2e-09,1.8e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15690000,0.98,-0.0077,-0.011,0.19,0.01,-0.0093,0.029,0.0072,-0.0054,0.019,-1.1e-05,-6.1e-05,4.9e-06,4e-05,2.7e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.044,0.045,0.0073,0.053,0.053,0.034,2e-09,2e-09,1.7e-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.0066,-0.0087,0.029,0.0055,-0.0042,0.02,-1.1e-05,-6.1e-05,5.6e-06,3.8e-05,3.1e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00017,0.00012,0.039,0.039,0.0073,0.046,0.046,0.034,1.8e-09,1.8e-09,1.7e-09,3.3e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15890000,0.98,-0.0077,-0.011,0.19,0.0055,-0.0071,0.03,0.0061,-0.005,0.02,-1.1e-05,-6.1e-05,5.1e-06,4.1e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00012,0.044,0.044,0.0074,0.053,0.053,0.034,1.8e-09,1.8e-09,1.6e-09,3.3e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -15990000,0.98,-0.0075,-0.011,0.19,0.0035,-0.0057,0.027,0.0048,-0.0038,0.019,-1.2e-05,-6.1e-05,5e-06,4.3e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.038,0.038,0.0074,0.046,0.046,0.034,1.7e-09,1.7e-09,1.6e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16090000,0.98,-0.0075,-0.011,0.19,0.0029,-0.0069,0.024,0.0051,-0.0045,0.019,-1.2e-05,-6.1e-05,4.7e-06,4.4e-05,2.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00017,0.00012,0.043,0.043,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.5e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16190000,0.98,-0.0074,-0.011,0.19,-0.001,-0.0046,0.023,0.0028,-0.0033,0.016,-1.2e-05,-6.1e-05,4.3e-06,4.5e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.038,0.038,0.0076,0.046,0.046,0.034,1.5e-09,1.5e-09,1.5e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16290000,0.98,-0.0075,-0.011,0.19,-0.0007,-0.0061,0.023,0.0026,-0.0039,0.017,-1.2e-05,-6.1e-05,4.4e-06,4.5e-05,2.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.043,0.043,0.0077,0.053,0.053,0.034,1.5e-09,1.5e-09,1.4e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16390000,0.98,-0.0074,-0.011,0.19,0.0017,-0.0054,0.023,0.0037,-0.0029,0.017,-1.2e-05,-6.1e-05,4.8e-06,5.1e-05,2.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00012,0.037,0.038,0.0077,0.046,0.046,0.034,1.4e-09,1.4e-09,1.4e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16490000,0.98,-0.0075,-0.011,0.19,0.0037,-0.007,0.026,0.0039,-0.0036,0.021,-1.2e-05,-6.1e-05,4.7e-06,5e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.042,0.042,0.0079,0.052,0.053,0.034,1.4e-09,1.4e-09,1.4e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -16590000,0.98,-0.0075,-0.011,0.19,0.0078,-0.0071,0.029,0.0034,-0.0028,0.021,-1.2e-05,-6.1e-05,4.6e-06,5.1e-05,3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00012,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1.3e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -16690000,0.98,-0.0076,-0.011,0.19,0.0092,-0.012,0.029,0.0043,-0.0037,0.022,-1.2e-05,-6.1e-05,4.9e-06,5.3e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00011,0.041,0.041,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,1.3e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -16790000,0.98,-0.0074,-0.011,0.19,0.01,-0.011,0.028,0.0033,-0.0027,0.022,-1.2e-05,-6.1e-05,5e-06,5.3e-05,3.2e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00015,0.00011,0.036,0.036,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,1.2e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -16890000,0.98,-0.0074,-0.011,0.19,0.0091,-0.011,0.029,0.0043,-0.0037,0.02,-1.2e-05,-6.1e-05,5.5e-06,5.6e-05,2.9e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00011,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,1.2e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -16990000,0.98,-0.0074,-0.011,0.19,0.0088,-0.01,0.029,0.0041,-0.0028,0.019,-1.2e-05,-6.1e-05,5.6e-06,6.2e-05,3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,1.2e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.0051,-0.004,0.018,-1.2e-05,-6.1e-05,5.4e-06,6.5e-05,2.8e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,1.1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -17190000,0.98,-0.0076,-0.011,0.19,0.0092,-0.018,0.03,0.0034,-0.0075,0.021,-1.2e-05,-6.1e-05,4.9e-06,6.3e-05,2.5e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.035,0.035,0.0083,0.046,0.046,0.034,9.7e-10,9.7e-10,1.1e-09,3.1e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -17290000,0.98,-0.0076,-0.011,0.19,0.01,-0.019,0.03,0.0044,-0.0093,0.021,-1.2e-05,-6.1e-05,4.5e-06,6.5e-05,2.3e-05,-0.0014,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.039,0.039,0.0084,0.052,0.052,0.034,9.7e-10,9.7e-10,1.1e-09,3.1e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0 -17390000,0.98,-0.0074,-0.011,0.19,0.0069,-0.018,0.029,0.0058,-0.0059,0.021,-1.3e-05,-6e-05,4.8e-06,7.3e-05,2.8e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.00011,0.035,0.035,0.0084,0.046,0.046,0.034,8.8e-10,8.8e-10,1.1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17490000,0.98,-0.0075,-0.011,0.19,0.005,-0.019,0.029,0.0063,-0.0077,0.023,-1.3e-05,-6e-05,4.6e-06,7.4e-05,2.8e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00014,0.00011,0.039,0.039,0.0085,0.052,0.052,0.034,8.8e-10,8.8e-10,1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17590000,0.98,-0.0074,-0.011,0.19,0.0011,-0.015,0.028,0.0025,-0.0058,0.02,-1.3e-05,-6.1e-05,4.6e-06,7.3e-05,3.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.00011,0.034,0.034,0.0085,0.046,0.046,0.034,7.9e-10,7.9e-10,1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17690000,0.98,-0.0074,-0.011,0.19,0.00021,-0.016,0.029,0.0026,-0.0073,0.023,-1.3e-05,-6.1e-05,4.6e-06,7.3e-05,3.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.0001,0.038,0.038,0.0086,0.052,0.052,0.034,7.9e-10,7.9e-10,9.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17790000,0.98,-0.0074,-0.011,0.19,0.0028,-0.014,0.029,0.0036,-0.0062,0.028,-1.4e-05,-6e-05,4.6e-06,7.7e-05,3.9e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00013,0.0001,0.033,0.033,0.0086,0.045,0.045,0.034,7.2e-10,7.2e-10,9.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17890000,0.98,-0.0073,-0.011,0.19,0.0049,-0.016,0.029,0.004,-0.0077,0.032,-1.4e-05,-6e-05,4.7e-06,7.6e-05,4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.0001,0.037,0.037,0.0086,0.052,0.052,0.035,7.2e-10,7.2e-10,9.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -17990000,0.98,-0.0071,-0.011,0.19,0.0043,-0.0093,0.029,0.0032,-0.002,0.033,-1.4e-05,-6e-05,4.7e-06,8e-05,5.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.033,0.033,0.0086,0.045,0.045,0.034,6.5e-10,6.5e-10,9.1e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -18090000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0098,0.028,0.0036,-0.003,0.031,-1.4e-05,-6e-05,4.6e-06,8.3e-05,4.8e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.036,0.036,0.0087,0.051,0.051,0.035,6.5e-10,6.5e-10,8.9e-10,3e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0 -18190000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0088,0.028,0.0042,-0.0022,0.029,-1.4e-05,-6e-05,5e-06,8.8e-05,4.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.032,0.032,0.0086,0.045,0.045,0.035,5.9e-10,5.9e-10,8.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18290000,0.98,-0.0072,-0.011,0.19,0.0048,-0.0093,0.027,0.0046,-0.0031,0.027,-1.4e-05,-6e-05,5e-06,9.1e-05,4.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.035,0.035,0.0087,0.051,0.051,0.035,5.9e-10,5.9e-10,8.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18390000,0.98,-0.0071,-0.011,0.19,0.0056,-0.008,0.027,0.0062,-0.0023,0.026,-1.4e-05,-6e-05,4.8e-06,9.6e-05,4.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.9e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.3e-10,5.3e-10,8.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18490000,0.98,-0.0072,-0.011,0.19,0.0084,-0.008,0.026,0.007,-0.0032,0.028,-1.4e-05,-6e-05,5e-06,9.7e-05,4.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,9.9e-05,0.034,0.034,0.0087,0.051,0.051,0.035,5.3e-10,5.3e-10,8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18590000,0.98,-0.007,-0.011,0.19,0.0068,-0.0074,0.026,0.0056,-0.0024,0.031,-1.5e-05,-6e-05,4.6e-06,9.6e-05,4.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.8e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.8e-10,4.8e-10,7.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18690000,0.98,-0.007,-0.011,0.19,0.0069,-0.0063,0.024,0.0063,-0.0031,0.029,-1.5e-05,-6e-05,4.8e-06,9.8e-05,4.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.7e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.8e-10,4.8e-10,7.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18790000,0.98,-0.007,-0.011,0.19,0.0058,-0.006,0.024,0.0063,-0.0025,0.027,-1.5e-05,-6e-05,4.7e-06,0.0001,4.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.6e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-10,4.4e-10,7.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18890000,0.98,-0.0069,-0.011,0.19,0.0045,-0.0056,0.021,0.0068,-0.0032,0.023,-1.5e-05,-6e-05,4.5e-06,0.00011,4.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.6e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,7.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -18990000,0.98,-0.0069,-0.011,0.19,0.0028,-0.0057,0.022,0.0056,-0.0025,0.026,-1.5e-05,-6e-05,4.5e-06,0.0001,4.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00011,9.5e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-10,4e-10,7.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.00087,-0.0062,0.023,0.0059,-0.0031,0.022,-1.5e-05,-6e-05,4.6e-06,0.00011,4.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.4e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19190000,0.98,-0.0069,-0.011,0.19,-0.00064,-0.0059,0.022,0.0049,-0.0025,0.022,-1.5e-05,-6e-05,4.2e-06,0.00011,4.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.4e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.6e-10,3.6e-10,6.8e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19290000,0.98,-0.0068,-0.011,0.19,-0.0015,-0.0057,0.023,0.0048,-0.0031,0.021,-1.5e-05,-6e-05,4.1e-06,0.00011,4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.3e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.6e-10,3.6e-10,6.7e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19390000,0.98,-0.0069,-0.011,0.19,-0.002,-0.0022,0.024,0.0041,-0.0012,0.019,-1.5e-05,-6e-05,3.9e-06,0.00011,4.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.2e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-10,3.3e-10,6.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19490000,0.98,-0.0069,-0.011,0.19,-0.0028,-0.0022,0.023,0.0039,-0.0014,0.019,-1.5e-05,-6e-05,3.6e-06,0.00011,4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.2e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,6.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19590000,0.98,-0.0069,-0.011,0.19,-0.0039,-0.0051,0.025,0.0044,-0.0024,0.019,-1.5e-05,-6e-05,3.4e-06,0.00012,3.7e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.1e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-10,3e-10,6.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19690000,0.98,-0.0069,-0.011,0.19,-0.0055,-0.0037,0.023,0.004,-0.0028,0.019,-1.5e-05,-6e-05,3.6e-06,0.00012,3.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,6.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19790000,0.98,-0.007,-0.011,0.19,-0.0056,-0.0022,0.022,0.0064,-0.0023,0.014,-1.5e-05,-6e-05,3.3e-06,0.00012,3.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,9e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-10,2.8e-10,6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19890000,0.98,-0.007,-0.011,0.19,-0.0056,-0.002,0.022,0.0058,-0.0025,0.013,-1.5e-05,-6e-05,3.2e-06,0.00013,3.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,8.9e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -19990000,0.98,-0.0071,-0.011,0.19,-0.0053,-0.0019,0.019,0.0062,-0.00091,0.0097,-1.5e-05,-5.9e-05,3.2e-06,0.00013,3.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.8e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20090000,0.98,-0.0071,-0.011,0.19,-0.0048,-0.0042,0.019,0.0056,-0.0012,0.013,-1.5e-05,-5.9e-05,3.1e-06,0.00013,3.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,8.8e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,5.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20190000,0.98,-0.0071,-0.011,0.19,-0.0038,-0.0016,0.02,0.0066,-0.00091,0.013,-1.5e-05,-5.9e-05,2.9e-06,0.00013,3.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.7e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20290000,0.98,-0.007,-0.011,0.19,-0.007,-0.0027,0.02,0.0061,-0.0011,0.013,-1.5e-05,-5.9e-05,2.8e-06,0.00013,3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.7e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20390000,0.98,-0.007,-0.011,0.19,-0.0077,-0.0015,0.021,0.0069,-0.00077,0.014,-1.5e-05,-5.9e-05,2.9e-06,0.00014,3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,8.6e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.006,-0.00095,0.012,-1.5e-05,-5.9e-05,2.8e-06,0.00014,2.8e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.6e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.007,-0.00079,0.011,-1.5e-05,-5.9e-05,3.1e-06,0.00014,2.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.9e-05,9.8e-05,8.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0058,-0.001,0.011,-1.5e-05,-5.9e-05,2.8e-06,0.00014,2.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,8.5e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.0004,0.0055,0.0049,-0.00081,0.0097,-1.5e-05,-5.9e-05,2.9e-06,0.00014,2.5e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.6e-05,8.4e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20890000,0.98,0.0028,-0.0073,0.19,-0.021,0.012,-0.11,0.003,-0.00013,0.0034,-1.5e-05,-5.9e-05,2.9e-06,0.00015,2.4e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.7e-05,8.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0023,0.00052,-0.011,-1.5e-05,-5.9e-05,2.8e-06,0.00015,2.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.6e-05,9.5e-05,8.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.7e-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.045,0.046,-0.37,-0.0016,0.0044,-0.042,-1.5e-05,-5.9e-05,2.8e-06,0.00015,2.3e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.7e-05,9.5e-05,8.2e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-10,1.7e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0012,0.0035,-0.078,-1.4e-05,-5.9e-05,2.8e-06,0.00015,1.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.3e-05,8.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.5e-10,1.5e-10,4.5e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21290000,0.98,-0.0005,-0.0072,0.19,-0.049,0.054,-0.63,-0.0061,0.0087,-0.14,-1.4e-05,-5.9e-05,2.5e-06,0.00015,1.6e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.4e-05,8.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.5e-10,1.5e-10,4.4e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-1.4e-05,-5.9e-05,2.5e-06,0.00015,1.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.1e-05,8.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,4.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0092,0.016,-0.29,-1.4e-05,-5.9e-05,2.6e-06,0.00015,1.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.2e-05,8e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,4.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.016,-0.38,-1.4e-05,-5.9e-05,2.7e-06,0.00015,1.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,9e-05,8e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,4.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-1.4e-05,-5.9e-05,2.9e-06,0.00015,9e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,9e-05,7.9e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,4.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0037,0.018,-0.61,-1.4e-05,-5.8e-05,3.1e-06,0.00016,6.9e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.8e-05,7.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0056,0.021,-0.75,-1.4e-05,-5.8e-05,2.9e-06,0.00016,5.6e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.8e-05,7.8e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00032,0.017,-0.89,-1.4e-05,-5.8e-05,3e-06,0.00015,7.9e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,7.8e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-10,1.1e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0016,0.019,-1,-1.4e-05,-5.8e-05,3.2e-06,0.00016,6.6e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,7.8e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.0061,0.013,-1.2,-1.4e-05,-5.8e-05,3.3e-06,0.00016,6.8e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.5e-05,8.4e-05,7.7e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22290000,0.98,-0.0069,-0.01,0.19,0.0017,0.0078,-1.4,0.006,0.014,-1.3,-1.4e-05,-5.8e-05,3.2e-06,0.00016,5.8e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.6e-05,8.4e-05,7.7e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22390000,0.98,-0.0072,-0.01,0.19,0.0067,-0.0018,-1.4,0.013,0.0042,-1.5,-1.4e-05,-5.8e-05,3e-06,0.00016,2e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,7.6e-05,0.021,0.021,0.0081,0.042,0.043,0.036,1e-10,1e-10,3.6e-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.0078,-1.4,0.014,0.0036,-1.6,-1.4e-05,-5.8e-05,2.8e-06,0.00016,1.3e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,7.6e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,3e-06,0.00016,-4.2e-07,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8.1e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-1.4e-05,-5.8e-05,2.9e-06,0.00016,-1.2e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.2e-05,7.5e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.7e-06,0.00016,-2.3e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,8e-05,7.5e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.8e-11,8.9e-11,3.4e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-1.4e-05,-5.8e-05,2.9e-06,0.00016,-3.1e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,8e-05,7.4e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3.3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,3.1e-06,0.00016,-4.5e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,7.4e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3.2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-1.4e-05,-5.8e-05,3.1e-06,0.00017,-4.8e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,7.3e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,3.2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-1.4e-05,-5.8e-05,2.9e-06,0.00017,-6.3e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,7.3e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-1.4e-05,-5.8e-05,3e-06,0.00017,-6.8e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,7.3e-05,0.019,0.02,0.0081,0.046,0.046,0.036,7.9e-11,7.9e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-1.4e-05,-5.8e-05,2.8e-06,0.00017,-4.1e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.2e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.5e-11,3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -23490000,0.98,-0.0079,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.9e-06,0.00017,-4.6e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,7.2e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.5e-11,7.5e-11,3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-1.4e-05,-5.8e-05,3e-06,0.00017,-5.8e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.1e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,2.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.9e-05,3.1e-06,0.00017,-6e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.1e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-1.4e-05,-5.8e-05,3.2e-06,0.00017,-6e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7.1e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.8e-11,6.8e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -23890000,0.98,-0.014,-0.021,0.18,0.053,-0.059,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00017,-6.1e-06,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.13,-0.089,-3.6,-1.4e-05,-5.8e-05,3.2e-06,0.00018,-1.1e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24090000,0.98,-0.016,-0.023,0.18,0.061,-0.066,0.09,0.13,-0.096,-3.6,-1.4e-05,-5.8e-05,3.1e-06,0.00018,-1.2e-05,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24190000,0.98,-0.013,-0.019,0.18,0.072,-0.071,0.077,0.14,-0.1,-3.6,-1.4e-05,-5.8e-05,3.2e-06,0.00019,-1.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-1.4e-05,-5.8e-05,3.2e-06,0.00019,-1.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-1.4e-05,-5.8e-05,3.4e-06,0.00019,-2.7e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-1.4e-05,-5.8e-05,3.6e-06,0.00019,-2.7e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-1.4e-05,-5.8e-05,3.6e-06,0.00019,-3.4e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24690000,0.98,-0.011,-0.014,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-1.4e-05,-5.8e-05,3.5e-06,0.00019,-3.4e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-1.5e-05,-5.8e-05,3.6e-06,0.00019,-4e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-1.5e-05,-5.8e-05,3.6e-06,0.00019,-4e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.6e-06,0.00019,-4.6e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-1.5e-05,-5.8e-05,3.6e-06,0.00019,-4.7e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.6e-05,6.6e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.5e-06,0.00019,-5.1e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.6e-05,6.6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.3e-06,0.00019,-5.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.6e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-1.5e-05,-5.8e-05,3.3e-06,0.00018,-5.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-11,5.1e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-1.5e-05,-5.8e-05,3.2e-06,0.00019,-5.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-11,5.1e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25590000,0.98,-0.011,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-1.5e-05,-5.8e-05,3.1e-06,0.00018,-6.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-1.5e-05,-5.8e-05,3.1e-06,0.00018,-6.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-1.6e-05,-5.8e-05,3e-06,0.00018,-6.6e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25890000,0.98,-0.011,-0.011,0.19,-0.0036,-0.029,0.019,0.17,-0.096,-3.6,-1.6e-05,-5.8e-05,2.8e-06,0.00019,-6.7e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -25990000,0.98,-0.011,-0.011,0.19,-0.012,-0.022,0.013,0.16,-0.086,-3.6,-1.6e-05,-5.8e-05,2.7e-06,0.00019,-7.1e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-1.6e-05,-5.8e-05,2.8e-06,0.00019,-7.1e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-1.6e-05,-5.8e-05,2.8e-06,0.00019,-7.3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26290000,0.98,-0.01,-0.012,0.18,-0.025,-0.014,0.00052,0.15,-0.083,-3.6,-1.6e-05,-5.8e-05,2.7e-06,0.00019,-7.3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26390000,0.98,-0.0098,-0.012,0.18,-0.031,-0.0065,0.0045,0.13,-0.075,-3.6,-1.6e-05,-5.8e-05,2.6e-06,0.00019,-7.6e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0034,0.014,0.13,-0.075,-3.6,-1.6e-05,-5.8e-05,2.5e-06,0.00019,-7.6e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0046,0.014,0.12,-0.068,-3.6,-1.6e-05,-5.8e-05,2.3e-06,0.00019,-7.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0097,0.013,0.12,-0.067,-3.6,-1.6e-05,-5.8e-05,2.1e-06,0.00019,-7.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-1.6e-05,-5.8e-05,2e-06,0.00019,-8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26890000,0.98,-0.008,-0.011,0.18,-0.051,0.016,0.007,0.1,-0.06,-3.6,-1.6e-05,-5.8e-05,2.1e-06,0.00019,-8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-1.6e-05,-5.8e-05,2e-06,0.00019,-8.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-1.6e-05,-5.8e-05,1.9e-06,0.0002,-8.3e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.035,0.011,0.071,-0.046,-3.6,-1.6e-05,-5.8e-05,1.8e-06,0.0002,-8.5e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27290000,0.98,-0.0075,-0.013,0.18,-0.073,0.041,0.12,0.064,-0.042,-3.6,-1.6e-05,-5.8e-05,1.8e-06,0.0002,-8.5e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27390000,0.98,-0.0089,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.0002,-8.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.03,-3.5,-1.6e-05,-5.8e-05,1.5e-06,0.0002,-8.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,6e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.5e-06,0.0002,-9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,6e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27690000,0.98,-0.0089,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-1.6e-05,-5.8e-05,1.5e-06,0.0002,-9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.049,0.75,0.025,-0.018,-3.3,-1.6e-05,-5.8e-05,1.5e-06,0.0002,-8.5e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -27890000,0.98,-0.0072,-0.012,0.18,-0.078,0.057,0.79,0.018,-0.012,-3.2,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-8.5e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,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 -27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-8.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0048,-3,-1.6e-05,-5.8e-05,1.5e-06,0.0002,-8.2e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0022,-0.0044,-3,-1.6e-05,-5.8e-05,1.4e-06,0.0002,-7.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0014,-2.9,-1.6e-05,-5.8e-05,1.5e-06,0.0002,-8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0043,-2.8,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-7.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,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 -28590000,0.98,-0.0072,-0.014,0.18,-0.083,0.06,0.79,-0.027,0.0084,-2.7,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-7.8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.7e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28690000,0.98,-0.007,-0.013,0.18,-0.083,0.061,0.79,-0.036,0.014,-2.6,-1.5e-05,-5.8e-05,1.4e-06,0.0002,-7.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.5e-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.5e-06,0.0002,-7.9e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -28890000,0.98,-0.0062,-0.012,0.18,-0.083,0.064,0.78,-0.046,0.023,-2.5,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-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.045,0.022,-2.4,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8.1e-05,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8.2e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.014,0.014,0.008,0.041,0.041,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 -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.5e-06,0.0002,-8.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-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 -29290000,0.98,-0.006,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.033,-2.2,-1.5e-05,-5.8e-05,1.5e-06,0.0002,-8.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.014,0.014,0.008,0.041,0.041,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 -29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-1.5e-05,-5.8e-05,1.6e-06,0.0002,-8.6e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-1.5e-05,-5.8e-05,1.7e-06,0.0002,-8.6e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.8e-06,0.0002,-8.8e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29690000,0.98,-0.0064,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-1.5e-05,-5.8e-05,1.8e-06,0.0002,-8.9e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29790000,0.98,-0.0063,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.043,-1.8,-1.4e-05,-5.8e-05,1.9e-06,0.0002,-9.2e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29890000,0.98,-0.0057,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-1.4e-05,-5.8e-05,2e-06,0.0002,-9.4e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-1.4e-05,-5.8e-05,2e-06,0.00021,-9.8e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30090000,0.98,-0.006,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.00021,-9.9e-05,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.4e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-1.4e-05,-5.7e-05,1.7e-06,0.00021,-0.0001,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30290000,0.98,-0.006,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-1.4e-05,-5.7e-05,1.8e-06,0.00021,-0.0001,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.4e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30390000,0.98,-0.006,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-1.4e-05,-5.7e-05,1.9e-06,0.00021,-0.00011,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30490000,0.98,-0.006,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-1.4e-05,-5.7e-05,1.9e-06,0.00021,-0.00011,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,2e-06,0.00022,-0.00011,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30690000,0.98,-0.0067,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,2e-06,0.00022,-0.00011,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.014,0.008,0.041,0.041,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30790000,0.98,-0.0064,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-1.4e-05,-5.7e-05,2e-06,0.00022,-0.00012,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-1.4e-05,-5.7e-05,2e-06,0.00022,-0.00012,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00012,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31090000,0.98,-0.0061,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-1.4e-05,-5.7e-05,1.9e-06,0.00023,-0.00012,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31190000,0.98,-0.0063,-0.013,0.19,-0.031,0.021,0.76,-0.052,0.046,-0.79,-1.4e-05,-5.7e-05,2e-06,0.00023,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-1.4e-05,-5.7e-05,2.1e-06,0.00023,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31390000,0.98,-0.0063,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-1.4e-05,-5.7e-05,2e-06,0.00023,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-1.4e-05,-5.7e-05,2e-06,0.00023,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31590000,0.98,-0.0059,-0.014,0.18,-0.018,0.0068,0.76,-0.038,0.039,-0.51,-1.4e-05,-5.7e-05,2.1e-06,0.00024,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31690000,0.98,-0.0059,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.44,-1.4e-05,-5.7e-05,2.2e-06,0.00024,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31790000,0.98,-0.0061,-0.015,0.18,-0.011,0.0032,0.76,-0.028,0.037,-0.36,-1.4e-05,-5.7e-05,2.2e-06,0.00024,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-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.00087,0.76,-0.029,0.038,-0.3,-1.4e-05,-5.7e-05,2.3e-06,0.00024,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -31990000,0.98,-0.0061,-0.015,0.18,-0.00013,0.00021,0.75,-0.017,0.034,-0.23,-1.3e-05,-5.7e-05,2.2e-06,0.00025,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32090000,0.98,-0.0065,-0.014,0.18,-0.00067,-0.0032,0.76,-0.017,0.034,-0.16,-1.3e-05,-5.7e-05,2.2e-06,0.00025,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-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 -32190000,0.98,-0.0067,-0.015,0.18,0.0046,-0.0064,0.76,-0.006,0.033,-0.092,-1.3e-05,-5.7e-05,2.2e-06,0.00025,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-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 -32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0091,0.75,-0.0055,0.032,-0.024,-1.3e-05,-5.7e-05,2.3e-06,0.00025,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5e-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 -32390000,0.98,-0.0067,-0.015,0.18,0.012,-0.01,0.75,0.0057,0.03,0.051,-1.3e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-1.3e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-11,2.8e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.074,-0.12,0.021,0.02,0.035,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.7e-05,5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-11,2.7e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-1.4e-05,-5.7e-05,2.2e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-11,2.7e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0044,-1.4e-05,-5.7e-05,2.3e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.6e-05,7.5e-05,5e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32890000,0.98,-0.0091,-0.013,0.18,0.033,-0.083,-0.13,0.038,0.0021,-0.011,-1.4e-05,-5.7e-05,2.3e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.6e-05,7.5e-05,4.9e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.001,-0.024,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.2e-05,7.1e-05,4.9e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-11,2.7e-11,9.4e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0091,-0.031,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00013,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.2e-05,7.1e-05,4.9e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-11,2.7e-11,9.3e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-1.4e-05,-5.6e-05,2.3e-06,0.00026,-0.00014,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6.6e-05,6.6e-05,4.9e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-11,2.6e-11,9.2e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00014,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6.7e-05,6.6e-05,4.9e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-11,2.6e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-1.4e-05,-5.6e-05,2.4e-06,0.00025,-0.00016,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6e-05,5.9e-05,4.9e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-11,2.6e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-1.4e-05,-5.6e-05,2.4e-06,0.00025,-0.00016,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6e-05,5.9e-05,4.9e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-11,2.6e-11,9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0 -33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-1.4e-05,-5.6e-05,2.5e-06,0.00025,-0.00018,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,5.3e-05,5.2e-05,4.8e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,8.9e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -33690000,0.98,-0.0077,-0.013,0.18,0.00081,-0.058,-0.11,0.063,-0.023,-0.077,-1.4e-05,-5.6e-05,2.5e-06,0.00025,-0.00018,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,5.3e-05,5.2e-05,4.8e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.048,-0.11,0.067,-0.018,-0.083,-1.4e-05,-5.6e-05,2.4e-06,0.00023,-0.00021,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.6e-05,4.6e-05,4.8e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-11,2.6e-11,8.7e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.046,-0.11,0.066,-0.023,-0.089,-1.4e-05,-5.6e-05,2.5e-06,0.00023,-0.00021,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.7e-05,4.6e-05,4.8e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-11,2.6e-11,8.7e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0 -33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-1.4e-05,-5.6e-05,2.4e-06,0.00021,-0.00024,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.1e-05,4.1e-05,4.8e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-1.4e-05,-5.6e-05,2.4e-06,0.00021,-0.00024,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.1e-05,4.1e-05,4.8e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.5e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0 -34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.021,-0.098,0.072,-0.013,-0.099,-1.4e-05,-5.6e-05,2.4e-06,0.00019,-0.00026,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.7e-05,3.6e-05,4.8e-05,0.047,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.5e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-1.4e-05,-5.6e-05,2.4e-06,0.00019,-0.00026,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.7e-05,3.6e-05,4.7e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-11,2.6e-11,8.4e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0 -34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.072,-0.01,-0.11,-1.4e-05,-5.6e-05,2.4e-06,0.00018,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.3e-05,3.3e-05,4.7e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-11,2.6e-11,8.3e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0096,-0.09,0.071,-0.011,-0.11,-1.4e-05,-5.6e-05,2.4e-06,0.00017,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.3e-05,3.3e-05,4.7e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-11,2.6e-11,8.3e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0 -34590000,0.98,-0.0068,-0.013,0.18,-0.014,-0.0053,0.71,0.073,-0.0089,-0.081,-1.4e-05,-5.6e-05,2.4e-06,0.00016,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.1e-05,3.1e-05,4.7e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8.2e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0032,1.7,0.071,-0.0093,0.038,-1.4e-05,-5.6e-05,2.3e-06,0.00016,-0.00027,-0.0011,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.1e-05,3.1e-05,4.7e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8.1e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0 -34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0014,2.7,0.072,-0.0069,0.21,-1.4e-05,-5.6e-05,2.3e-06,0.00018,-0.00029,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.00017,2.9e-05,2.9e-05,4.7e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-11,2.6e-11,8.1e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 -34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0038,3.6,0.07,-0.0065,0.5,-1.4e-05,-5.6e-05,2.3e-06,0.00018,-0.00029,-0.001,0.37,0.0037,0.025,0,0,0,0,0,0.00017,2.9e-05,2.9e-05,4.7e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-11,2.6e-11,8e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0 +10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.8e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.8e-07,0.0025,0.0025,0.005,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +90000,0.98,-0.0095,-0.012,0.18,-5.5e-05,-0.0032,-0.024,-3.6e-06,-0.00014,-0.0021,0,0,0,0,0,0,0.2,-4.7e-10,0.43,0,0,0,0,0,9e-07,0.0026,0.0026,0.0051,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +190000,0.98,-0.0091,-0.013,0.21,-0.0013,-0.0036,-0.037,-4.4e-05,-0.00046,-0.017,5.2e-10,-4.3e-10,-3e-12,0,0,-6.8e-08,0.2,0.012,0.43,0,0,0,0,0,2.9e-06,0.0027,0.0027,0.0052,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +290000,0.98,-0.0092,-0.013,0.21,-0.0016,-0.0053,-0.046,-0.00015,-0.00032,-0.018,4.4e-09,-5.5e-09,1.1e-11,0,0,-2.9e-06,0.2,0.012,0.43,0,0,0,0,0,7.1e-06,0.0029,0.0029,0.0054,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +390000,0.98,-0.0095,-0.013,0.19,-0.00033,-0.0065,-0.063,-0.00029,-0.00087,-0.013,-6.7e-09,-6.3e-09,-1.6e-10,0,0,8.8e-06,0.2,0.002,0.44,0,0,0,0,0,1.3e-05,0.0031,0.0031,0.0056,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +490000,0.98,-0.0095,-0.014,0.19,0.0016,-0.0061,-0.069,2.4e-05,-0.00049,-0.011,-1.2e-06,6.5e-07,4.2e-08,0,0,1.6e-05,0.2,0.002,0.44,0,0,0,0,0,2e-05,0.0034,0.0034,0.0058,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +590000,0.98,-0.0095,-0.014,0.19,0.0014,-0.0091,-0.12,0.00018,-0.0013,-0.029,-1.4e-06,6.7e-07,4.3e-08,0,0,6.4e-05,0.2,0.002,0.44,0,0,0,0,0,2.9e-05,0.0037,0.0037,0.0062,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +690000,0.98,-0.0096,-0.014,0.19,0.0032,-0.0083,-0.05,0.00021,-0.00076,-0.0088,-5.6e-06,1.3e-06,1.6e-07,0,0,-9.5e-05,0.2,0.002,0.44,0,0,0,0,0,4e-05,0.004,0.004,0.0065,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +790000,0.98,-0.0096,-0.014,0.19,0.0059,-0.009,-0.054,0.0006,-0.0016,-0.011,-5.5e-06,1.3e-06,1.6e-07,0,0,-0.00013,0.2,0.002,0.44,0,0,0,0,0,5.3e-05,0.0044,0.0044,0.0069,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +890000,0.98,-0.0096,-0.015,0.19,0.006,-0.0068,-0.093,0.00052,-0.00095,-0.031,-2.2e-05,1.6e-07,4.9e-07,0,0,-3.3e-05,0.2,0.002,0.44,0,0,0,0,0,6.7e-05,0.0048,0.0048,0.0074,1.3,1.3,1.3,0.2,0.2,0.25,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +990000,0.98,-0.0096,-0.015,0.19,0.0091,-0.0071,-0.12,0.0013,-0.0017,-0.046,-2.2e-05,1.2e-07,4.9e-07,0,0,1.3e-05,0.2,0.002,0.44,0,0,0,0,0,8.3e-05,0.0053,0.0053,0.0079,1.5,1.5,0.95,0.3,0.3,0.23,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1090000,0.98,-0.0096,-0.015,0.19,0.015,-0.0083,-0.13,0.0012,-0.0011,-0.062,-6.1e-05,-1.7e-05,9.8e-07,0,0,4.5e-05,0.2,0.002,0.44,0,0,0,0,0,0.0001,0.0057,0.0057,0.0084,0.92,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1190000,0.98,-0.0096,-0.015,0.19,0.021,-0.011,-0.11,0.003,-0.0021,-0.047,-5.8e-05,-1.5e-05,9.8e-07,0,0,-0.00048,0.2,0.002,0.44,0,0,0,0,0,0.00012,0.0063,0.0063,0.009,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1290000,0.98,-0.0093,-0.016,0.19,0.024,-0.0097,-0.11,0.0027,-0.0016,-0.048,-0.00017,-0.0001,1.5e-06,0,0,-0.00075,0.2,0.002,0.44,0,0,0,0,0,0.00014,0.0064,0.0064,0.0097,0.88,0.88,0.41,0.15,0.15,0.18,0.0095,0.0095,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1390000,0.98,-0.0093,-0.016,0.19,0.033,-0.012,-0.097,0.0056,-0.0027,-0.038,-0.00016,-9.6e-05,1.5e-06,0,0,-0.0014,0.2,0.002,0.44,0,0,0,0,0,0.00016,0.0071,0.0071,0.01,1.1,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1490000,0.98,-0.009,-0.016,0.19,0.03,-0.01,-0.12,0.0044,-0.0018,-0.053,-0.00039,-0.00034,1.2e-06,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.00019,0.0067,0.0067,0.011,0.95,0.95,0.27,0.14,0.14,0.15,0.0089,0.0089,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1590000,0.98,-0.0091,-0.016,0.19,0.037,-0.012,-0.13,0.0077,-0.003,-0.063,-0.00039,-0.00034,1.2e-06,0,0,-0.0014,0.2,0.002,0.44,0,0,0,0,0,0.00022,0.0074,0.0074,0.012,1.3,1.3,0.23,0.2,0.2,0.14,0.0089,0.0089,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1690000,0.98,-0.0088,-0.016,0.19,0.033,-0.0083,-0.13,0.0054,-0.0019,-0.068,-0.00073,-0.00075,-3.2e-07,0,0,-0.0018,0.2,0.002,0.44,0,0,0,0,0,0.00024,0.0064,0.0064,0.013,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1790000,0.98,-0.009,-0.016,0.19,0.042,-0.0099,-0.13,0.0092,-0.0029,-0.067,-0.00073,-0.00074,-2.5e-07,0,0,-0.0028,0.2,0.002,0.44,0,0,0,0,0,0.00027,0.007,0.007,0.014,1.3,1.3,0.16,0.2,0.2,0.12,0.0078,0.0078,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +1890000,0.98,-0.0089,-0.016,0.19,0.049,-0.0086,-0.14,0.014,-0.0037,-0.075,-0.00072,-0.00074,-2.1e-07,0,0,-0.0032,0.2,0.002,0.44,0,0,0,0,0,0.0003,0.0076,0.0076,0.015,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +1990000,0.98,-0.0085,-0.016,0.19,0.039,-0.0042,-0.14,0.0096,-0.0021,-0.074,-0.0011,-0.0013,-3.5e-06,0,0,-0.0046,0.2,0.002,0.44,0,0,0,0,0,0.00034,0.0061,0.0061,0.016,1.3,1.3,0.13,0.2,0.2,0.11,0.0066,0.0066,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +2090000,0.98,-0.0086,-0.016,0.19,0.046,-0.0041,-0.14,0.014,-0.0026,-0.071,-0.0011,-0.0013,-3.3e-06,0,0,-0.0065,0.2,0.002,0.44,0,0,0,0,0,0.00037,0.0066,0.0066,0.017,1.7,1.7,0.12,0.31,0.31,0.11,0.0066,0.0066,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +2190000,0.98,-0.0082,-0.015,0.19,0.035,-0.0012,-0.14,0.0091,-0.0012,-0.077,-0.0014,-0.0018,-8.5e-06,0,0,-0.0075,0.2,0.002,0.44,0,0,0,0,0,0.00041,0.005,0.005,0.018,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,0.01,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2290000,0.98,-0.0082,-0.016,0.19,0.04,8.5e-05,-0.14,0.013,-0.0012,-0.075,-0.0014,-0.0018,-8.3e-06,0,0,-0.0098,0.2,0.002,0.44,0,0,0,0,0,0.00045,0.0054,0.0054,0.019,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,0.01,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2390000,0.98,-0.008,-0.015,0.19,0.031,0.0011,-0.14,0.0082,-0.00046,-0.072,-0.0017,-0.0023,-1.4e-05,0,0,-0.012,0.2,0.002,0.44,0,0,0,0,0,0.00049,0.004,0.004,0.02,1,1,0.1,0.19,0.19,0.098,0.0045,0.0045,0.01,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2490000,0.98,-0.0079,-0.015,0.19,0.033,0.0031,-0.14,0.011,-0.00026,-0.079,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0.2,0.002,0.44,0,0,0,0,0,0.00053,0.0044,0.0044,0.021,1.3,1.3,0.1,0.28,0.28,0.097,0.0045,0.0045,0.01,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +2590000,0.98,-0.0078,-0.015,0.19,0.023,0.0022,-0.15,0.0069,8.6e-05,-0.085,-0.0018,-0.0027,-2e-05,0,0,-0.015,0.2,0.002,0.44,0,0,0,0,0,0.00057,0.0032,0.0032,0.022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,0.01,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +2690000,0.98,-0.0078,-0.015,0.19,0.027,0.0043,-0.15,0.0095,0.00041,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0.2,0.002,0.44,0,0,0,0,0,0.00062,0.0035,0.0035,0.024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,0.01,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +2790000,0.98,-0.0077,-0.015,0.19,0.021,0.0046,-0.14,0.006,0.00052,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0.2,0.002,0.44,0,0,0,0,0,0.00066,0.0027,0.0027,0.025,0.77,0.77,0.096,0.16,0.16,0.089,0.0032,0.0032,0.01,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +2890000,0.98,-0.0077,-0.015,0.19,0.025,0.0043,-0.14,0.0084,0.00092,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.025,0.2,0.002,0.44,0,0,0,0,0,0.00071,0.0029,0.0029,0.027,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,0.01,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +2990000,0.98,-0.0076,-0.015,0.19,0.019,0.0032,-0.15,0.0054,0.00069,-0.086,-0.002,-0.0033,-3e-05,0,0,-0.028,0.2,0.002,0.44,0,0,0,0,0,0.00076,0.0023,0.0023,0.028,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,0.01,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +3090000,0.98,-0.0076,-0.015,0.19,0.026,0.0024,-0.15,0.0077,0.00092,-0.087,-0.002,-0.0033,-2.9e-05,0,0,-0.031,0.2,0.002,0.44,0,0,0,0,0,0.00081,0.0025,0.0025,0.03,0.82,0.82,0.095,0.22,0.22,0.086,0.0027,0.0027,0.01,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +3190000,0.98,-0.0076,-0.015,0.19,0.021,0.001,-0.15,0.0052,0.00052,-0.097,-0.002,-0.0036,-3.4e-05,0,0,-0.033,0.2,0.002,0.44,0,0,0,0,0,0.00087,0.002,0.002,0.031,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,0.01,0.04,0.04,0.031,0,0,0,0,0,0,0,0 +3290000,0.98,-0.0075,-0.015,0.19,0.024,0.0019,-0.15,0.0075,0.00061,-0.11,-0.002,-0.0036,-3.3e-05,0,0,-0.034,0.2,0.002,0.44,0,0,0,0,0,0.00092,0.0022,0.0022,0.033,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,0.01,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +3390000,0.98,-0.0073,-0.014,0.19,0.019,0.0032,-0.15,0.0051,0.00045,-0.1,-0.0021,-0.0038,-3.7e-05,0,0,-0.04,0.2,0.002,0.44,0,0,0,0,0,0.00098,0.0017,0.0017,0.034,0.53,0.53,0.095,0.14,0.14,0.085,0.0019,0.0019,0.01,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +3490000,0.98,-0.0072,-0.014,0.19,0.024,0.0064,-0.15,0.0073,0.00092,-0.1,-0.0021,-0.0038,-3.6e-05,0,0,-0.044,0.2,0.002,0.44,0,0,0,0,0,0.001,0.0019,0.0019,0.036,0.65,0.65,0.095,0.19,0.19,0.086,0.0019,0.0019,0.01,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +3590000,0.98,-0.0071,-0.014,0.19,0.021,0.0056,-0.15,0.0051,0.00081,-0.11,-0.0022,-0.004,-4e-05,0,0,-0.047,0.2,0.002,0.44,0,0,0,0,0,0.0011,0.0015,0.0015,0.038,0.48,0.48,0.094,0.13,0.13,0.086,0.0016,0.0016,0.01,0.04,0.04,0.026,0,0,0,0,0,0,0,0 +3690000,0.98,-0.0071,-0.014,0.19,0.023,0.0071,-0.15,0.0074,0.0014,-0.11,-0.0021,-0.004,-4e-05,0,0,-0.052,0.2,0.002,0.44,0,0,0,0,0,0.0012,0.0017,0.0017,0.04,0.59,0.59,0.093,0.18,0.18,0.085,0.0016,0.0016,0.01,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +3790000,0.98,-0.007,-0.014,0.19,0.018,0.0097,-0.15,0.005,0.0012,-0.11,-0.0022,-0.0042,-4.5e-05,0,0,-0.055,0.2,0.002,0.44,0,0,0,0,0,0.0012,0.0014,0.0014,0.042,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,0.01,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +3890000,0.98,-0.007,-0.014,0.19,0.019,0.011,-0.14,0.0069,0.0023,-0.11,-0.0022,-0.0042,-4.5e-05,0,0,-0.059,0.2,0.002,0.44,0,0,0,0,0,0.0013,0.0015,0.0015,0.043,0.54,0.54,0.091,0.17,0.17,0.086,0.0014,0.0014,0.01,0.04,0.04,0.022,0,0,0,0,0,0,0,0 +3990000,0.98,-0.007,-0.014,0.19,0.023,0.013,-0.14,0.0091,0.0035,-0.11,-0.0022,-0.0042,-4.4e-05,0,0,-0.064,0.2,0.002,0.44,0,0,0,0,0,0.0014,0.0017,0.0017,0.045,0.66,0.66,0.089,0.22,0.22,0.085,0.0014,0.0014,0.01,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +4090000,0.98,-0.0069,-0.014,0.19,0.02,0.011,-0.12,0.0067,0.0028,-0.098,-0.0022,-0.0044,-5e-05,0,0,-0.072,0.2,0.002,0.44,0,0,0,0,0,0.0014,0.0013,0.0013,0.047,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,0.01,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +4190000,0.98,-0.007,-0.014,0.19,0.023,0.011,-0.12,0.0088,0.0039,-0.1,-0.0022,-0.0044,-5e-05,0,0,-0.074,0.2,0.002,0.44,0,0,0,0,0,0.0015,0.0015,0.0015,0.049,0.6,0.6,0.086,0.21,0.21,0.086,0.0012,0.0012,0.01,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +4290000,0.98,-0.0071,-0.014,0.19,0.02,0.01,-0.12,0.0064,0.0029,-0.11,-0.0022,-0.0046,-5.6e-05,0,0,-0.077,0.2,0.002,0.44,0,0,0,0,0,0.0016,0.0012,0.0012,0.052,0.46,0.46,0.084,0.15,0.15,0.085,0.00096,0.00096,0.01,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +4390000,0.98,-0.0071,-0.014,0.19,0.024,0.01,-0.11,0.0087,0.0039,-0.094,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0.2,0.002,0.44,0,0,0,0,0,0.0017,0.0013,0.0013,0.054,0.56,0.56,0.081,0.2,0.2,0.084,0.00096,0.00096,0.01,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +4490000,0.98,-0.0072,-0.014,0.19,0.02,0.01,-0.11,0.0064,0.0029,-0.095,-0.0021,-0.0048,-6.1e-05,0,0,-0.086,0.2,0.002,0.44,0,0,0,0,0,0.0017,0.0011,0.0011,0.056,0.43,0.43,0.08,0.14,0.14,0.085,0.00079,0.00079,0.01,0.04,0.04,0.015,0,0,0,0,0,0,0,0 +4590000,0.98,-0.0071,-0.014,0.19,0.023,0.01,-0.11,0.0085,0.0039,-0.098,-0.0021,-0.0048,-6.1e-05,0,0,-0.089,0.2,0.002,0.44,0,0,0,0,0,0.0018,0.0011,0.0011,0.058,0.51,0.51,0.077,0.19,0.19,0.084,0.00079,0.00079,0.01,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +4690000,0.98,-0.0071,-0.013,0.19,0.017,0.0083,-0.1,0.0062,0.0029,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0.2,0.002,0.44,0,0,0,0,0,0.0019,0.00093,0.00092,0.06,0.39,0.39,0.074,0.14,0.14,0.083,0.00065,0.00065,0.01,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +4790000,0.98,-0.007,-0.013,0.19,0.014,0.0094,-0.099,0.0078,0.0038,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0.2,0.002,0.44,0,0,0,0,0,0.002,0.001,0.001,0.063,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,0.01,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +4890000,0.98,-0.007,-0.013,0.19,0.01,0.0054,-0.093,0.0052,0.0026,-0.088,-0.0021,-0.0051,-7.1e-05,0,0,-0.099,0.2,0.002,0.44,0,0,0,0,0,0.0021,0.00081,0.00081,0.065,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,0.01,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +4990000,0.98,-0.0069,-0.013,0.19,0.014,0.0072,-0.085,0.0064,0.0033,-0.083,-0.0021,-0.0051,-7.1e-05,0,0,-0.1,0.2,0.002,0.44,0,0,0,0,0,0.0021,0.00088,0.00087,0.068,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,0.01,0.04,0.04,0.01,0,0,0,0,0,0,0,0 +5090000,0.98,-0.0069,-0.013,0.19,0.01,0.0064,-0.082,0.0045,0.0023,-0.081,-0.0021,-0.0052,-7.4e-05,0,0,-0.1,0.2,0.002,0.44,0,0,0,0,0,0.0022,0.00071,0.0007,0.07,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,0.01,0.04,0.04,0.0098,0,0,0,0,0,0,0,0 +5190000,0.98,-0.0067,-0.013,0.19,0.0089,0.0096,-0.08,0.0054,0.0031,-0.079,-0.0021,-0.0052,-7.4e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0023,0.00076,0.00075,0.073,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,0.01,0.04,0.04,0.0091,0,0,0,0,0,0,0,0 +5290000,0.98,-0.0066,-0.013,0.19,0.0071,0.0092,-0.068,0.0037,0.0024,-0.072,-0.0021,-0.0053,-7.7e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0024,0.00061,0.00061,0.075,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,0.01,0.04,0.04,0.0084,0,0,0,0,0,0,0,0 +5390000,0.98,-0.0065,-0.013,0.19,0.0055,0.012,-0.065,0.0044,0.0034,-0.067,-0.0021,-0.0053,-7.7e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0025,0.00066,0.00065,0.078,0.36,0.36,0.057,0.15,0.15,0.079,0.00035,0.00035,0.01,0.04,0.04,0.0078,0,0,0,0,0,0,0,0 +5490000,0.98,-0.0066,-0.013,0.19,0.0043,0.013,-0.06,0.0028,0.0028,-0.065,-0.0021,-0.0054,-8.1e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0026,0.00053,0.00053,0.08,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,0.01,0.04,0.04,0.0073,0,0,0,0,0,0,0,0 +5590000,0.98,-0.0066,-0.013,0.19,0.0043,0.017,-0.053,0.0033,0.0044,-0.058,-0.0021,-0.0054,-8.1e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0027,0.00057,0.00056,0.083,0.32,0.32,0.053,0.15,0.15,0.078,0.00028,0.00028,0.01,0.04,0.04,0.0067,0,0,0,0,0,0,0,0 +5690000,0.98,-0.0067,-0.013,0.19,0.0034,0.017,-0.052,0.0022,0.0036,-0.055,-0.002,-0.0054,-8.7e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0028,0.00046,0.00045,0.086,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,0.01,0.04,0.04,0.0062,0,0,0,0,0,0,0,0 +5790000,0.98,-0.0065,-0.013,0.19,0.004,0.02,-0.049,0.0026,0.0054,-0.053,-0.002,-0.0054,-8.7e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0029,0.00049,0.00049,0.089,0.29,0.29,0.05,0.14,0.14,0.077,0.00023,0.00023,0.01,0.04,0.04,0.0058,0,0,0,0,0,0,0,0 +5890000,0.98,-0.0066,-0.013,0.19,0.005,0.018,-0.048,0.0018,0.0044,-0.056,-0.0019,-0.0055,-9.5e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.003,0.0004,0.00039,0.092,0.23,0.23,0.048,0.1,0.1,0.075,0.00019,0.00019,0.01,0.04,0.04,0.0054,0,0,0,0,0,0,0,0 +5990000,0.98,-0.0065,-0.013,0.19,0.0061,0.019,-0.041,0.0024,0.0062,-0.05,-0.0019,-0.0055,-9.5e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0031,0.00043,0.00042,0.095,0.27,0.27,0.045,0.13,0.13,0.074,0.00019,0.00019,0.01,0.04,0.04,0.005,0,0,0,0,0,0,0,0 +6090000,0.98,-0.0065,-0.013,0.19,0.0058,0.021,-0.039,0.003,0.0082,-0.047,-0.0019,-0.0055,-9.5e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0032,0.00046,0.00045,0.098,0.31,0.31,0.044,0.17,0.17,0.074,0.00019,0.00019,0.01,0.04,0.04,0.0047,0,0,0,0,0,0,0,0 +6190000,0.98,-0.0066,-0.013,0.19,0.0037,0.019,-0.037,0.0022,0.0066,-0.047,-0.0019,-0.0056,-0.0001,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0033,0.00037,0.00036,0.1,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,0.01,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 +6290000,0.98,-0.0066,-0.013,0.19,0.0022,0.021,-0.041,0.0025,0.0085,-0.053,-0.0019,-0.0056,-0.0001,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0034,0.00039,0.00039,0.1,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,0.01,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 +6390000,0.98,-0.0067,-0.013,0.19,0.0032,0.018,-0.042,0.0017,0.0068,-0.056,-0.0018,-0.0056,-0.00015,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.0003,0.0003,0.0035,0.2,0.2,0.039,0.12,0.12,0.072,0.00012,0.00012,0.01,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 +6490000,0.98,-0.0066,-0.013,0.19,0.00096,0.017,-0.039,0.0019,0.0085,-0.053,-0.0018,-0.0056,-0.00054,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.0003,0.0003,0.0015,0.21,0.21,0.038,0.15,0.15,0.07,0.00012,0.00012,0.0099,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 +6590000,0.98,-0.0065,-0.013,0.19,0.00025,0.02,-0.042,0.002,0.01,-0.056,-0.0018,-0.0056,-0.00096,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.0003,0.0003,0.001,0.21,0.21,0.036,0.18,0.18,0.069,0.00012,0.00012,0.0098,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 +6690000,0.98,-0.0064,-0.013,0.19,-0.0024,0.022,-0.044,0.0018,0.012,-0.057,-0.0019,-0.0056,-0.0017,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0003,0.0003,0.0008,0.22,0.22,0.035,0.22,0.22,0.068,0.00012,0.00012,0.0096,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 +6790000,0.98,-0.0064,-0.013,0.19,-0.00064,0.024,-0.042,0.0016,0.015,-0.058,-0.0019,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0003,0.0003,0.00071,0.23,0.24,0.034,0.26,0.26,0.068,0.00012,0.00012,0.0092,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 +6890000,0.98,-0.0062,-0.013,0.19,-0.0011,0.024,-0.038,0.0016,0.017,-0.055,-0.0019,-0.0056,-0.0023,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00066,0.25,0.25,0.032,0.31,0.31,0.067,0.00012,0.00012,0.0087,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 +6990000,0.98,-0.0062,-0.013,0.19,-0.0011,0.026,-0.037,0.0014,0.019,-0.055,-0.0019,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00063,0.27,0.27,0.031,0.36,0.36,0.066,0.00012,0.00012,0.0081,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 +7090000,0.98,-0.0061,-0.012,0.19,-0.002,0.031,-0.037,0.0013,0.022,-0.056,-0.0019,-0.0056,-0.0019,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00064,0.29,0.29,0.03,0.42,0.42,0.066,0.00012,0.00012,0.0075,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 +7190000,0.98,-0.006,-0.013,0.19,-0.0025,0.034,-0.036,0.00097,0.026,-0.058,-0.0019,-0.0055,-0.0025,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00032,0.00032,0.00063,0.32,0.32,0.029,0.49,0.49,0.065,0.00012,0.00012,0.0067,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 +7290000,0.98,-0.006,-0.013,0.19,-0.0017,0.038,-0.034,0.00073,0.029,-0.054,-0.0019,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00032,0.00032,0.00063,0.35,0.35,0.028,0.56,0.56,0.064,0.00012,0.00012,0.0059,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 +7390000,0.98,-0.0058,-0.013,0.19,-0.0034,0.041,-0.032,0.00052,0.033,-0.052,-0.0019,-0.0056,-0.0016,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00033,0.00033,0.00064,0.38,0.38,0.027,0.64,0.64,0.064,0.00012,0.00012,0.0053,0.04,0.04,0.002,0,0,0,0,0,0,0,0 +7490000,0.98,-0.0058,-0.013,0.19,-0.0011,0.045,-0.026,0.00041,0.038,-0.046,-0.0018,-0.0056,-0.00028,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.00063,0.42,0.42,0.026,0.73,0.73,0.063,0.00012,0.00012,0.0046,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 +7590000,0.98,-0.0059,-0.013,0.19,-9.4e-05,0.048,-0.023,0.00036,0.042,-0.041,-0.0018,-0.0056,-9.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.00061,0.45,0.45,0.025,0.83,0.83,0.062,0.00012,0.00012,0.004,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 +7690000,0.98,-0.0059,-0.013,0.19,-0.00044,0.052,-0.022,0.00033,0.047,-0.036,-0.0018,-0.0056,-0.00028,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.00061,0.5,0.5,0.025,0.95,0.95,0.062,0.00012,0.00012,0.0035,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 +7790000,0.98,-0.0058,-0.013,0.19,0.0012,0.054,-0.024,0.00034,0.052,-0.041,-0.0018,-0.0056,-0.0007,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.00059,0.54,0.54,0.024,1.1,1.1,0.061,0.00012,0.00012,0.003,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 +7890000,0.98,-0.0058,-0.013,0.19,-0.00018,0.059,-0.025,0.0003,0.057,-0.045,-0.0018,-0.0056,-0.00085,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.00057,0.59,0.59,0.023,1.2,1.2,0.06,0.00012,0.00012,0.0026,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 +7990000,0.98,-0.0057,-0.013,0.19,7.8e-05,0.062,-0.021,0.0003,0.062,-0.041,-0.0018,-0.0056,-0.00067,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.00055,0.64,0.64,0.022,1.4,1.4,0.059,0.00012,0.00012,0.0022,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8090000,0.98,-0.0056,-0.013,0.19,0.0016,0.067,-0.022,0.00037,0.069,-0.044,-0.0018,-0.0056,-0.0017,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00038,0.00038,0.00054,0.7,0.7,0.022,1.5,1.5,0.059,0.00012,0.00012,0.002,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8190000,0.98,-0.0056,-0.013,0.19,0.0022,0.073,-0.018,0.00053,0.076,-0.038,-0.0019,-0.0056,-0.0022,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00039,0.00039,0.00052,0.76,0.76,0.021,1.7,1.7,0.058,0.00012,0.00012,0.0017,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 +8290000,0.98,-0.0056,-0.013,0.19,0.0044,0.077,-0.016,0.00085,0.082,-0.038,-0.0018,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0004,0.0004,0.0005,0.81,0.81,0.02,1.9,1.9,0.057,0.00012,0.00012,0.0015,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8390000,0.98,-0.0056,-0.013,0.19,0.0022,0.08,-0.015,0.0012,0.09,-0.036,-0.0018,-0.0056,-0.0021,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00041,0.00041,0.00049,0.88,0.88,0.02,2.2,2.2,0.057,0.00012,0.00012,0.0013,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8490000,0.98,-0.0055,-0.013,0.19,0.002,0.084,-0.017,0.0014,0.096,-0.041,-0.0018,-0.0056,-0.0014,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00042,0.00042,0.00047,0.94,0.94,0.019,2.4,2.4,0.056,0.00011,0.00011,0.0012,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8590000,0.98,-0.0054,-0.013,0.19,0.0031,0.088,-0.012,0.0016,0.1,-0.036,-0.0018,-0.0056,-0.0015,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00043,0.00043,0.00045,1,1,0.018,2.7,2.7,0.055,0.00011,0.00011,0.001,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8690000,0.98,-0.0055,-0.013,0.19,0.003,0.089,-0.014,0.0019,0.11,-0.037,-0.0018,-0.0056,-0.0013,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00043,0.00043,0.00045,1.1,1.1,0.018,2.9,2.9,0.055,0.00011,0.00011,0.00094,0.04,0.04,0.001,0,0,0,0,0,0,0,0 +8790000,0.98,-0.0054,-0.013,0.19,0.0045,0.093,-0.013,0.0021,0.12,-0.035,-0.0018,-0.0056,-0.0016,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00045,0.00045,0.00043,1.2,1.2,0.018,3.3,3.3,0.055,0.00011,0.00011,0.00084,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 +8890000,0.98,-0.0055,-0.013,0.19,0.0045,0.095,-0.0091,0.0025,0.13,-0.029,-0.0018,-0.0056,-0.0011,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00045,0.00045,0.00041,1.2,1.2,0.017,3.6,3.6,0.054,0.00011,0.00011,0.00075,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 +8990000,0.98,-0.0054,-0.013,0.19,0.0035,0.1,-0.0083,0.0029,0.14,-0.032,-0.0018,-0.0056,-0.00059,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.00041,1.3,1.3,0.017,4,4,0.054,0.00011,0.00011,0.00068,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 +9090000,0.98,-0.0055,-0.013,0.19,0.0038,0.1,-0.0093,0.0032,0.14,-0.032,-0.0017,-0.0056,-8.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.00039,1.3,1.3,0.016,4.2,4.2,0.053,0.00011,0.00011,0.00061,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 +9190000,0.98,-0.0054,-0.013,0.19,0.0073,0.11,-0.0088,0.0037,0.15,-0.032,-0.0017,-0.0056,0.00027,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00038,1.4,1.4,0.016,4.7,4.7,0.052,0.00011,0.00011,0.00055,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 +9290000,0.98,-0.0053,-0.013,0.19,0.0095,0.11,-0.0072,0.0045,0.15,-0.03,-0.0017,-0.0056,0.00036,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00037,1.5,1.5,0.015,5,5,0.052,0.00011,0.00011,0.0005,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 +9390000,0.98,-0.0052,-0.013,0.19,0.0097,0.11,-0.0061,0.0055,0.16,-0.03,-0.0017,-0.0056,-2.3e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00048,0.00048,0.00036,1.6,1.6,0.015,5.5,5.5,0.052,0.00011,0.00011,0.00046,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 +9490000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0044,0.0061,0.17,-0.027,-0.0017,-0.0057,0.00012,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00035,1.6,1.6,0.015,5.8,5.8,0.051,0.0001,0.0001,0.00042,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 +9590000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0043,0.0069,0.18,-0.028,-0.0017,-0.0056,-0.00045,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00034,1.7,1.7,0.014,6.4,6.4,0.05,0.0001,0.0001,0.00038,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 +9690000,0.98,-0.0054,-0.013,0.19,0.0091,0.11,-0.0014,0.0074,0.18,-0.027,-0.0017,-0.0056,-0.00056,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00033,1.7,1.7,0.014,6.6,6.6,0.05,9.9e-05,0.0001,0.00035,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 +9790000,0.98,-0.0054,-0.013,0.19,0.011,0.11,-0.0027,0.0084,0.19,-0.028,-0.0017,-0.0056,-0.001,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00032,1.8,1.8,0.014,7.3,7.3,0.05,9.9e-05,0.0001,0.00032,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 +9890000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0014,0.0088,0.18,-0.029,-0.0017,-0.0057,-0.00084,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00031,1.8,1.8,0.013,7.4,7.4,0.049,9.6e-05,9.7e-05,0.0003,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 +9990000,0.98,-0.0054,-0.013,0.19,0.014,0.11,-0.00073,0.01,0.2,-0.031,-0.0017,-0.0057,-0.0011,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00031,1.9,1.9,0.013,8.2,8.2,0.049,9.6e-05,9.7e-05,0.00027,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 +10090000,0.98,-0.0055,-0.013,0.19,0.012,0.11,0.00048,0.011,0.19,-0.029,-0.0016,-0.0057,-0.0014,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.0003,1.9,1.9,0.013,8.2,8.2,0.048,9.3e-05,9.3e-05,0.00025,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 +10190000,0.98,-0.0054,-0.013,0.19,0.011,0.11,0.0014,0.012,0.2,-0.03,-0.0016,-0.0057,-0.0017,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00048,0.00048,0.00029,2,2,0.012,9,9,0.048,9.3e-05,9.3e-05,0.00023,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 +10290000,0.98,-0.0055,-0.013,0.19,0.011,0.11,0.00029,0.013,0.21,-0.029,-0.0016,-0.0057,-0.0015,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00028,2.1,2.1,0.012,9.9,9.9,0.048,9.3e-05,9.3e-05,0.00022,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 +10390000,0.98,-0.0055,-0.013,0.19,0.007,0.0051,-0.0025,0.00075,0.00014,-0.028,-0.0016,-0.0057,-0.0013,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00051,0.00051,0.00028,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-05,9.3e-05,0.0002,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10490000,0.98,-0.0054,-0.012,0.19,0.0083,0.0074,0.007,0.0015,0.00073,-0.023,-0.0016,-0.0057,-0.0015,-1.2e-06,8.4e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00027,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-05,9.3e-05,0.00019,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10590000,0.98,-0.0053,-0.012,0.19,-0.0013,0.0053,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-0.0012,0.00032,5.4e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00026,0.13,0.13,0.27,0.13,0.13,0.055,9.3e-05,9.3e-05,0.00017,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10690000,0.98,-0.0053,-0.012,0.19,-0.00024,0.0064,0.016,-0.0013,-0.0049,-0.017,-0.0016,-0.0057,-0.0013,0.00032,6.1e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00055,0.00055,0.00026,0.14,0.14,0.26,0.14,0.14,0.065,9.3e-05,9.3e-05,0.00016,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10790000,0.98,-0.0054,-0.012,0.19,0.0016,0.0029,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-0.0012,0.00052,0.00047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00054,0.00054,0.00025,0.1,0.1,0.17,0.091,0.091,0.062,9e-05,9e-05,0.00015,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10890000,0.98,-0.0053,-0.013,0.19,0.0016,0.0063,0.01,-0.00062,-0.0043,-0.018,-0.0016,-0.0057,-0.00088,0.00052,0.00047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00056,0.00056,0.00025,0.12,0.12,0.16,0.098,0.098,0.068,9e-05,9e-05,0.00014,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10990000,0.98,-0.0054,-0.013,0.19,0.0011,0.012,0.016,-0.00046,-0.003,-0.011,-0.0016,-0.0057,-0.00091,0.00066,0.00071,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00024,0.092,0.092,0.12,0.073,0.073,0.065,8.6e-05,8.6e-05,0.00014,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11090000,0.98,-0.0055,-0.013,0.19,0.0021,0.017,0.02,-0.00034,-0.0016,-0.0074,-0.0016,-0.0057,-0.0011,0.00066,0.00071,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00054,0.00054,0.00024,0.11,0.11,0.11,0.08,0.08,0.069,8.6e-05,8.6e-05,0.00013,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11190000,0.98,-0.0058,-0.013,0.19,0.0037,0.017,0.026,0.001,-0.0018,-0.00035,-0.0015,-0.0057,-0.0012,0.00063,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00049,0.00049,0.00023,0.092,0.092,0.083,0.063,0.063,0.066,8e-05,8e-05,0.00012,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11290000,0.98,-0.0058,-0.013,0.19,0.0039,0.018,0.026,0.0014,2.5e-05,-0.00012,-0.0015,-0.0057,-0.0012,0.00064,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00051,0.00051,0.00023,0.11,0.11,0.077,0.07,0.07,0.069,8e-05,8e-05,0.00011,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11390000,0.98,-0.0059,-0.013,0.19,0.0023,0.016,0.016,0.00086,-0.00079,-0.0086,-0.0014,-0.0058,-0.0011,0.0012,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00044,0.00044,0.00023,0.093,0.093,0.062,0.057,0.057,0.066,7.4e-05,7.4e-05,0.00011,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11490000,0.98,-0.0058,-0.013,0.19,0.0013,0.017,0.02,0.00098,0.00085,-0.0025,-0.0014,-0.0058,-0.001,0.0012,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00046,0.00046,0.00022,0.11,0.11,0.057,0.065,0.065,0.067,7.4e-05,7.4e-05,0.0001,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11590000,0.98,-0.0062,-0.012,0.19,0.0032,0.013,0.018,0.00082,-0.00023,-0.0036,-0.0014,-0.0058,-0.00097,0.0015,0.003,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00039,0.00039,0.00022,0.092,0.092,0.048,0.054,0.054,0.065,6.7e-05,6.7e-05,9.5e-05,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11690000,0.98,-0.0061,-0.012,0.19,0.0036,0.017,0.018,0.0012,0.0013,-0.0049,-0.0014,-0.0058,-0.00087,0.0015,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0004,0.0004,0.00021,0.11,0.11,0.044,0.062,0.062,0.066,6.7e-05,6.7e-05,9e-05,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11790000,0.98,-0.0065,-0.012,0.19,0.0023,0.011,0.019,0.00068,-0.0016,-0.002,-0.0013,-0.0059,-0.00063,0.0021,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00034,0.00034,0.00021,0.09,0.09,0.037,0.052,0.052,0.063,6.2e-05,6.2e-05,8.5e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11890000,0.98,-0.0066,-0.012,0.19,0.005,0.013,0.017,0.001,-0.00042,-0.0013,-0.0013,-0.0059,-0.00063,0.0021,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00035,0.00035,0.00021,0.11,0.11,0.034,0.06,0.06,0.063,6.2e-05,6.2e-05,8e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11990000,0.98,-0.0068,-0.012,0.19,0.0079,0.013,0.015,0.0021,-0.0016,-0.0049,-0.0012,-0.0059,-0.00054,0.0021,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0003,0.0003,0.0002,0.086,0.086,0.03,0.051,0.051,0.061,5.7e-05,5.7e-05,7.6e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12090000,0.98,-0.0067,-0.012,0.19,0.0095,0.013,0.018,0.003,-0.00037,0.0011,-0.0012,-0.0059,-0.00051,0.002,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00031,0.00031,0.0002,0.1,0.1,0.027,0.059,0.059,0.06,5.7e-05,5.7e-05,7.2e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12190000,0.98,-0.0066,-0.012,0.19,0.0077,0.012,0.017,0.0018,0.00055,0.0029,-0.0012,-0.0059,-0.00054,0.0023,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00027,0.00027,0.0002,0.081,0.081,0.024,0.05,0.05,0.058,5.3e-05,5.3e-05,6.9e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12290000,0.98,-0.0067,-0.012,0.19,0.0054,0.011,0.016,0.0025,0.0017,0.0039,-0.0012,-0.0059,-0.00056,0.0023,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00028,0.00028,0.00019,0.096,0.096,0.022,0.059,0.059,0.058,5.3e-05,5.3e-05,6.6e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12390000,0.98,-0.0068,-0.012,0.19,0.004,0.0078,0.014,0.0017,0.00065,-0.0021,-0.0012,-0.0059,-0.00053,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00025,0.00025,0.00019,0.076,0.076,0.02,0.05,0.05,0.056,4.9e-05,4.9e-05,6.2e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +12490000,0.98,-0.0068,-0.012,0.19,0.004,0.0089,0.018,0.0021,0.0015,-6.6e-05,-0.0012,-0.0059,-0.00051,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00026,0.00026,0.00019,0.089,0.089,0.018,0.058,0.058,0.055,4.9e-05,4.9e-05,5.9e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +12590000,0.98,-0.007,-0.012,0.19,0.0078,0.0022,0.02,0.0033,-0.0012,0.0017,-0.0012,-0.0059,-0.00049,0.0026,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00023,0.00023,0.00018,0.071,0.071,0.017,0.049,0.049,0.054,4.7e-05,4.7e-05,5.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +12690000,0.98,-0.007,-0.012,0.19,0.0083,0.0001,0.019,0.004,-0.0011,0.0033,-0.0012,-0.0059,-0.00046,0.0026,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00024,0.00024,0.00018,0.083,0.083,0.016,0.058,0.058,0.053,4.7e-05,4.7e-05,5.4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +12790000,0.98,-0.0072,-0.012,0.19,0.0099,-0.0034,0.021,0.0041,-0.0042,0.0054,-0.0011,-0.0059,-0.00026,0.0027,0.0047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00022,0.00022,0.00018,0.067,0.067,0.014,0.049,0.049,0.052,4.4e-05,4.4e-05,5.2e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +12890000,0.98,-0.0072,-0.012,0.19,0.01,-0.0042,0.022,0.0051,-0.0046,0.0085,-0.0011,-0.0059,-0.00013,0.0027,0.0047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00023,0.00023,0.00018,0.077,0.077,0.013,0.058,0.058,0.051,4.4e-05,4.4e-05,4.9e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +12990000,0.98,-0.0072,-0.012,0.19,0.008,-0.0023,0.022,0.0036,-0.0034,0.0096,-0.0011,-0.006,-1.1e-05,0.0028,0.0046,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.063,0.063,0.012,0.049,0.049,0.05,4.2e-05,4.2e-05,4.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13090000,0.98,-0.0072,-0.012,0.19,0.0089,-0.0022,0.02,0.0044,-0.0036,0.0085,-0.0011,-0.006,0.00013,0.0028,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00022,0.00022,0.00017,0.072,0.072,0.012,0.057,0.057,0.049,4.2e-05,4.2e-05,4.5e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13190000,0.98,-0.0072,-0.012,0.19,0.0039,-0.0039,0.019,0.00095,-0.0044,0.0091,-0.0011,-0.006,0.00022,0.0029,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.059,0.059,0.011,0.049,0.049,0.047,4e-05,4e-05,4.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0048,0.016,0.0013,-0.0048,0.0085,-0.0011,-0.006,0.00024,0.0029,0.0044,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.067,0.067,0.01,0.057,0.057,0.047,4e-05,4e-05,4.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13390000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0029,0.016,0.00084,-0.0036,0.0091,-0.0011,-0.006,0.0002,0.003,0.0044,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.056,0.056,0.0097,0.049,0.049,0.046,3.8e-05,3.8e-05,4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13490000,0.98,-0.0072,-0.012,0.19,0.0031,-0.0012,0.015,0.0011,-0.0038,0.0053,-0.0011,-0.006,0.00024,0.0031,0.0043,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00016,0.063,0.063,0.0093,0.056,0.056,0.045,3.8e-05,3.8e-05,3.8e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0015,0.017,0.004,-0.0031,0.0038,-0.0011,-0.006,0.00022,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.053,0.053,0.0088,0.048,0.048,0.044,3.6e-05,3.6e-05,3.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13690000,0.98,-0.0071,-0.012,0.19,0.0076,-0.0029,0.017,0.0047,-0.0033,0.0064,-0.0011,-0.006,0.00029,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.06,0.06,0.0085,0.056,0.056,0.044,3.6e-05,3.6e-05,3.5e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13790000,0.98,-0.0071,-0.012,0.19,0.015,0.0012,0.017,0.0083,-0.00086,0.0059,-0.0011,-0.0059,0.00026,0.0036,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.05,0.05,0.0082,0.048,0.048,0.043,3.5e-05,3.5e-05,3.4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13890000,0.98,-0.007,-0.012,0.19,0.016,0.0019,0.018,0.0098,-0.00069,0.0081,-0.0011,-0.0059,0.00034,0.0036,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.057,0.057,0.008,0.056,0.056,0.042,3.5e-05,3.5e-05,3.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +13990000,0.98,-0.007,-0.012,0.19,0.015,0.002,0.017,0.0073,-0.0022,0.007,-0.0011,-0.006,0.00042,0.0034,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00015,0.048,0.048,0.0077,0.048,0.048,0.041,3.3e-05,3.3e-05,3.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0024,0.018,0.0088,-0.0023,0.0034,-0.0011,-0.0059,0.00026,0.0035,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.055,0.055,0.0076,0.055,0.055,0.041,3.3e-05,3.3e-05,3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14190000,0.98,-0.007,-0.012,0.19,0.01,-0.0012,0.018,0.008,-0.0017,0.0036,-0.0011,-0.006,0.00019,0.0036,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00015,0.046,0.046,0.0074,0.048,0.048,0.04,3.1e-05,3.1e-05,2.9e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0012,0.016,0.009,-0.0018,0.0079,-0.0011,-0.006,0.0002,0.0036,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.052,0.052,0.0073,0.055,0.055,0.04,3.1e-05,3.1e-05,2.8e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0042,0.017,0.0084,-0.003,0.012,-0.0011,-0.006,0.00025,0.0035,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.045,0.045,0.0071,0.048,0.048,0.039,3e-05,3e-05,2.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0039,0.021,0.0095,-0.0034,0.015,-0.0011,-0.006,0.00018,0.0034,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00014,0.051,0.051,0.0071,0.055,0.055,0.038,3e-05,3e-05,2.6e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14590000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0041,0.019,0.0059,-0.0041,0.011,-0.0011,-0.006,0.00017,0.0032,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.044,0.044,0.007,0.047,0.047,0.038,2.8e-05,2.8e-05,2.5e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14690000,0.98,-0.0072,-0.011,0.19,0.0073,-0.0041,0.019,0.0067,-0.0045,0.011,-0.0011,-0.006,0.0002,0.0033,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.049,0.049,0.007,0.054,0.054,0.037,2.8e-05,2.8e-05,2.4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14790000,0.98,-0.0072,-0.011,0.19,0.009,0.0028,0.019,0.0053,0.00086,0.014,-0.0012,-0.006,0.00029,0.0033,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.042,0.042,0.0069,0.047,0.047,0.037,2.6e-05,2.6e-05,2.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14890000,0.98,-0.0071,-0.011,0.19,0.0077,0.00045,0.023,0.0061,0.001,0.014,-0.0012,-0.006,0.00035,0.0034,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.048,0.048,0.007,0.054,0.054,0.037,2.6e-05,2.6e-05,2.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14990000,0.98,-0.0072,-0.011,0.19,0.0064,-0.0012,0.026,0.0048,-0.00061,0.017,-0.0012,-0.006,0.00039,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.042,0.042,0.0069,0.047,0.047,0.036,2.5e-05,2.5e-05,2.2e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15090000,0.98,-0.0072,-0.011,0.19,0.0065,-0.00011,0.03,0.0054,-0.00072,0.019,-0.0012,-0.006,0.00038,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.047,0.047,0.007,0.054,0.054,0.036,2.5e-05,2.5e-05,2.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15190000,0.98,-0.0073,-0.011,0.19,0.0046,-0.0012,0.03,0.0042,-0.00067,0.021,-0.0012,-0.0061,0.00036,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.041,0.041,0.007,0.047,0.047,0.036,2.3e-05,2.3e-05,2e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15290000,0.98,-0.0074,-0.011,0.19,0.0052,-0.0023,0.03,0.0048,-0.00083,0.018,-0.0012,-0.0061,0.00042,0.0034,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.046,0.046,0.0071,0.054,0.054,0.035,2.3e-05,2.3e-05,2e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15390000,0.98,-0.0075,-0.011,0.19,0.0054,8.3e-05,0.029,0.0038,-0.00056,0.018,-0.0012,-0.0061,0.00041,0.0035,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.04,0.04,0.007,0.047,0.047,0.035,2.1e-05,2.1e-05,1.9e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15490000,0.98,-0.0075,-0.011,0.19,0.0048,-0.0024,0.029,0.0043,-0.00065,0.019,-0.0012,-0.0061,0.00041,0.0036,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.045,0.045,0.0072,0.053,0.053,0.035,2.1e-05,2.1e-05,1.8e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.0063,0.029,0.0063,-0.0046,0.018,-0.0011,-0.0061,0.00045,0.0039,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.04,0.04,0.0072,0.046,0.046,0.035,2e-05,2e-05,1.8e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15690000,0.98,-0.0077,-0.011,0.19,0.01,-0.0093,0.029,0.0072,-0.0054,0.019,-0.0011,-0.0061,0.00049,0.004,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.044,0.045,0.0073,0.053,0.053,0.034,2e-05,2e-05,1.7e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15790000,0.98,-0.0077,-0.011,0.19,0.0066,-0.0087,0.029,0.0055,-0.0042,0.02,-0.0011,-0.0061,0.00056,0.0038,0.0031,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00017,0.00012,0.039,0.039,0.0073,0.046,0.046,0.034,1.8e-05,1.8e-05,1.7e-05,0.033,0.034,0.0005,0,0,0,0,0,0,0,0 +15890000,0.98,-0.0077,-0.011,0.19,0.0055,-0.0071,0.03,0.0061,-0.005,0.02,-0.0011,-0.0061,0.00051,0.0041,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00012,0.044,0.044,0.0074,0.053,0.053,0.034,1.8e-05,1.8e-05,1.6e-05,0.033,0.034,0.0005,0,0,0,0,0,0,0,0 +15990000,0.98,-0.0075,-0.011,0.19,0.0035,-0.0057,0.027,0.0048,-0.0038,0.019,-0.0012,-0.0061,0.0005,0.0043,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.038,0.038,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,1.6e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16090000,0.98,-0.0075,-0.011,0.19,0.0029,-0.0069,0.024,0.0051,-0.0045,0.019,-0.0012,-0.0061,0.00047,0.0044,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00017,0.00012,0.043,0.043,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,1.5e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16190000,0.98,-0.0074,-0.011,0.19,-0.001,-0.0046,0.023,0.0028,-0.0033,0.016,-0.0012,-0.0061,0.00043,0.0045,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.038,0.038,0.0076,0.046,0.046,0.034,1.5e-05,1.5e-05,1.5e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16290000,0.98,-0.0075,-0.011,0.19,-0.0007,-0.0061,0.023,0.0026,-0.0039,0.017,-0.0012,-0.0061,0.00044,0.0045,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.043,0.043,0.0077,0.053,0.053,0.034,1.5e-05,1.5e-05,1.4e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16390000,0.98,-0.0074,-0.011,0.19,0.0017,-0.0054,0.023,0.0037,-0.0029,0.017,-0.0012,-0.0061,0.00048,0.0051,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00012,0.037,0.038,0.0077,0.046,0.046,0.034,1.4e-05,1.4e-05,1.4e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16490000,0.98,-0.0075,-0.011,0.19,0.0037,-0.007,0.026,0.0039,-0.0036,0.021,-0.0012,-0.0061,0.00047,0.005,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.042,0.042,0.0079,0.052,0.053,0.034,1.4e-05,1.4e-05,1.4e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16590000,0.98,-0.0075,-0.011,0.19,0.0078,-0.0071,0.029,0.0034,-0.0028,0.021,-0.0012,-0.0061,0.00046,0.0051,0.003,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00012,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,1.3e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16690000,0.98,-0.0076,-0.011,0.19,0.0092,-0.012,0.029,0.0043,-0.0037,0.022,-0.0012,-0.0061,0.00049,0.0053,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00011,0.041,0.041,0.008,0.052,0.052,0.034,1.3e-05,1.3e-05,1.3e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16790000,0.98,-0.0074,-0.011,0.19,0.01,-0.011,0.028,0.0033,-0.0027,0.022,-0.0012,-0.0061,0.0005,0.0053,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00015,0.00011,0.036,0.036,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,1.2e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16890000,0.98,-0.0074,-0.011,0.19,0.0091,-0.011,0.029,0.0043,-0.0037,0.02,-0.0012,-0.0061,0.00055,0.0056,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00011,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,1.2e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16990000,0.98,-0.0074,-0.011,0.19,0.0088,-0.01,0.029,0.0041,-0.0028,0.019,-0.0012,-0.0061,0.00056,0.0062,0.003,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,1.2e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.0051,-0.004,0.018,-0.0012,-0.0061,0.00054,0.0065,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17190000,0.98,-0.0076,-0.011,0.19,0.0092,-0.018,0.03,0.0034,-0.0075,0.021,-0.0012,-0.0061,0.00049,0.0063,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.035,0.035,0.0083,0.046,0.046,0.034,9.7e-06,9.7e-06,1.1e-05,0.031,0.032,0.0005,0,0,0,0,0,0,0,0 +17290000,0.98,-0.0076,-0.011,0.19,0.01,-0.019,0.03,0.0044,-0.0093,0.021,-0.0012,-0.0061,0.00045,0.0065,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.039,0.039,0.0084,0.052,0.052,0.034,9.7e-06,9.7e-06,1.1e-05,0.031,0.032,0.0005,0,0,0,0,0,0,0,0 +17390000,0.98,-0.0074,-0.011,0.19,0.0069,-0.018,0.029,0.0058,-0.0059,0.021,-0.0013,-0.006,0.00048,0.0073,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.00011,0.035,0.035,0.0084,0.046,0.046,0.034,8.8e-06,8.8e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17490000,0.98,-0.0075,-0.011,0.19,0.005,-0.019,0.029,0.0063,-0.0077,0.023,-0.0013,-0.006,0.00046,0.0074,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00014,0.00011,0.039,0.039,0.0085,0.052,0.052,0.034,8.8e-06,8.8e-06,1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17590000,0.98,-0.0074,-0.011,0.19,0.0011,-0.015,0.028,0.0025,-0.0058,0.02,-0.0013,-0.0061,0.00046,0.0073,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.00011,0.034,0.034,0.0085,0.046,0.046,0.034,7.9e-06,7.9e-06,1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17690000,0.98,-0.0074,-0.011,0.19,0.00021,-0.016,0.029,0.0026,-0.0073,0.023,-0.0013,-0.0061,0.00046,0.0073,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.0001,0.038,0.038,0.0086,0.052,0.052,0.034,7.9e-06,7.9e-06,9.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17790000,0.98,-0.0074,-0.011,0.19,0.0028,-0.014,0.029,0.0036,-0.0062,0.028,-0.0014,-0.006,0.00046,0.0077,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00013,0.0001,0.033,0.033,0.0086,0.045,0.045,0.034,7.2e-06,7.2e-06,9.5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17890000,0.98,-0.0073,-0.011,0.19,0.0049,-0.016,0.029,0.004,-0.0077,0.032,-0.0014,-0.006,0.00047,0.0076,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.0001,0.037,0.037,0.0086,0.052,0.052,0.035,7.2e-06,7.2e-06,9.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17990000,0.98,-0.0071,-0.011,0.19,0.0043,-0.0093,0.029,0.0032,-0.002,0.033,-0.0014,-0.006,0.00047,0.008,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.033,0.033,0.0086,0.045,0.045,0.034,6.5e-06,6.5e-06,9.1e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18090000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0098,0.028,0.0036,-0.003,0.031,-0.0014,-0.006,0.00046,0.0083,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.036,0.036,0.0087,0.051,0.051,0.035,6.5e-06,6.5e-06,8.9e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18190000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0088,0.028,0.0042,-0.0022,0.029,-0.0014,-0.006,0.0005,0.0088,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.032,0.032,0.0086,0.045,0.045,0.035,5.9e-06,5.9e-06,8.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18290000,0.98,-0.0072,-0.011,0.19,0.0048,-0.0093,0.027,0.0046,-0.0031,0.027,-0.0014,-0.006,0.0005,0.0091,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.035,0.035,0.0087,0.051,0.051,0.035,5.9e-06,5.9e-06,8.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18390000,0.98,-0.0071,-0.011,0.19,0.0056,-0.008,0.027,0.0062,-0.0023,0.026,-0.0014,-0.006,0.00048,0.0096,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.9e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.3e-06,5.3e-06,8.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18490000,0.98,-0.0072,-0.011,0.19,0.0084,-0.008,0.026,0.007,-0.0032,0.028,-0.0014,-0.006,0.0005,0.0097,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,9.9e-05,0.034,0.034,0.0087,0.051,0.051,0.035,5.3e-06,5.3e-06,8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18590000,0.98,-0.007,-0.011,0.19,0.0068,-0.0074,0.026,0.0056,-0.0024,0.031,-0.0015,-0.006,0.00046,0.0096,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.8e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.8e-06,4.8e-06,7.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18690000,0.98,-0.007,-0.011,0.19,0.0069,-0.0063,0.024,0.0063,-0.0031,0.029,-0.0015,-0.006,0.00048,0.0098,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.7e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.8e-06,4.8e-06,7.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18790000,0.98,-0.007,-0.011,0.19,0.0058,-0.006,0.024,0.0063,-0.0025,0.027,-0.0015,-0.006,0.00047,0.01,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.6e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,7.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18890000,0.98,-0.0069,-0.011,0.19,0.0045,-0.0056,0.021,0.0068,-0.0032,0.023,-0.0015,-0.006,0.00045,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.6e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,7.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18990000,0.98,-0.0069,-0.011,0.19,0.0028,-0.0057,0.022,0.0056,-0.0025,0.026,-0.0015,-0.006,0.00045,0.01,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00011,9.5e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,7.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19090000,0.98,-0.007,-0.011,0.19,0.00087,-0.0062,0.023,0.0059,-0.0031,0.022,-0.0015,-0.006,0.00046,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.4e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19190000,0.98,-0.0069,-0.011,0.19,-0.00064,-0.0059,0.022,0.0049,-0.0025,0.022,-0.0015,-0.006,0.00042,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.4e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.6e-06,3.6e-06,6.8e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19290000,0.98,-0.0068,-0.011,0.19,-0.0015,-0.0057,0.023,0.0048,-0.0031,0.021,-0.0015,-0.006,0.00041,0.011,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.3e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.6e-06,3.6e-06,6.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19390000,0.98,-0.0069,-0.011,0.19,-0.002,-0.0022,0.024,0.0041,-0.0012,0.019,-0.0015,-0.006,0.00039,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.2e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,6.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19490000,0.98,-0.0069,-0.011,0.19,-0.0028,-0.0022,0.023,0.0039,-0.0014,0.019,-0.0015,-0.006,0.00036,0.011,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.2e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19590000,0.98,-0.0069,-0.011,0.19,-0.0039,-0.0051,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,0.00034,0.012,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.1e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,6.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19690000,0.98,-0.0069,-0.011,0.19,-0.0055,-0.0037,0.023,0.004,-0.0028,0.019,-0.0015,-0.006,0.00036,0.012,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,6.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19790000,0.98,-0.007,-0.011,0.19,-0.0056,-0.0022,0.022,0.0064,-0.0023,0.014,-0.0015,-0.006,0.00033,0.012,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,9e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19890000,0.98,-0.007,-0.011,0.19,-0.0056,-0.002,0.022,0.0058,-0.0025,0.013,-0.0015,-0.006,0.00032,0.013,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,8.9e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,5.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19990000,0.98,-0.0071,-0.011,0.19,-0.0053,-0.0019,0.019,0.0062,-0.00091,0.0097,-0.0015,-0.0059,0.00032,0.013,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.8e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,5.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20090000,0.98,-0.0071,-0.011,0.19,-0.0048,-0.0042,0.019,0.0056,-0.0012,0.013,-0.0015,-0.0059,0.00031,0.013,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,8.8e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,5.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20190000,0.98,-0.0071,-0.011,0.19,-0.0038,-0.0016,0.02,0.0066,-0.0009,0.013,-0.0015,-0.0059,0.00029,0.013,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.7e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,5.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20290000,0.98,-0.007,-0.011,0.19,-0.007,-0.0027,0.02,0.0061,-0.0011,0.013,-0.0015,-0.0059,0.00028,0.013,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.7e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,5.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20390000,0.98,-0.007,-0.011,0.19,-0.0077,-0.0015,0.021,0.0069,-0.00077,0.014,-0.0015,-0.0059,0.00029,0.014,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,8.6e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,5.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.006,-0.00095,0.012,-0.0015,-0.0059,0.00028,0.014,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.6e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,5.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.007,-0.00079,0.011,-0.0015,-0.0059,0.00031,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.9e-05,9.8e-05,8.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0058,-0.001,0.011,-0.0015,-0.0059,0.00028,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,8.5e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.0004,0.0055,0.0049,-0.00081,0.0097,-0.0015,-0.0059,0.00029,0.014,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.6e-05,8.4e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,4.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20890000,0.98,0.0028,-0.0073,0.19,-0.021,0.012,-0.11,0.003,-0.00013,0.0034,-0.0015,-0.0059,0.00029,0.015,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.7e-05,8.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,4.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0023,0.00052,-0.011,-0.0015,-0.0059,0.00028,0.015,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.6e-05,9.5e-05,8.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,4.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21090000,0.98,0.0045,-0.0042,0.19,-0.045,0.046,-0.37,-0.0016,0.0044,-0.042,-0.0015,-0.0059,0.00028,0.015,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.7e-05,9.5e-05,8.2e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,4.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0012,0.0035,-0.078,-0.0014,-0.0059,0.00028,0.015,0.0016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.3e-05,8.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.5e-06,1.5e-06,4.5e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.98,-0.0005,-0.0072,0.19,-0.049,0.054,-0.63,-0.0061,0.0087,-0.14,-0.0014,-0.0059,0.00025,0.015,0.0016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.4e-05,8.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.5e-06,1.5e-06,4.4e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,0.00025,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.1e-05,8.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,4.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0092,0.016,-0.29,-0.0014,-0.0059,0.00026,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.2e-05,8e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,4.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.016,-0.38,-0.0014,-0.0059,0.00027,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,9e-05,8e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,4.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,0.00029,0.015,0.0009,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,9e-05,7.9e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,4.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0037,0.018,-0.61,-0.0014,-0.0058,0.00031,0.016,0.00068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.8e-05,7.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0056,0.021,-0.75,-0.0014,-0.0058,0.00029,0.016,0.00056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.8e-05,7.8e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,3.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00032,0.017,-0.89,-0.0014,-0.0058,0.0003,0.015,0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,7.8e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,3.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0016,0.019,-1,-0.0014,-0.0058,0.00032,0.016,0.00066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,7.8e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-06,1.1e-06,3.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.0061,0.013,-1.2,-0.0014,-0.0058,0.00033,0.016,0.00068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.5e-05,8.4e-05,7.7e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22290000,0.98,-0.0069,-0.01,0.19,0.0017,0.0078,-1.4,0.006,0.014,-1.3,-0.0014,-0.0058,0.00032,0.016,0.00058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.6e-05,8.4e-05,7.7e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22390000,0.98,-0.0072,-0.01,0.19,0.0067,-0.0018,-1.4,0.013,0.0042,-1.5,-0.0014,-0.0058,0.0003,0.016,0.0002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,7.6e-05,0.021,0.021,0.0081,0.042,0.043,0.036,1e-06,1e-06,3.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0078,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,0.00028,0.016,0.00013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,7.6e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,3.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,0.0003,0.016,-4.2e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8.1e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,3.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,0.00029,0.016,-0.00012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.2e-05,7.5e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-07,9.4e-07,3.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,0.00027,0.016,-0.00023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,8e-05,7.5e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,3.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,0.00029,0.016,-0.00031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,8e-05,7.4e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,3.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,0.00031,0.016,-0.00045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,7.4e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,3.2e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,0.00031,0.017,-0.00048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,7.3e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,3.2e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,0.00029,0.017,-0.00063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,7.3e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-07,7.9e-07,3.1e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,0.0003,0.017,-0.00068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,7.3e-05,0.019,0.02,0.0081,0.046,0.046,0.036,7.9e-07,7.9e-07,3.1e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,0.00028,0.017,-0.00041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.2e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-07,7.5e-07,3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +23490000,0.98,-0.0079,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,0.00029,0.017,-0.00046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,7.2e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.5e-07,7.5e-07,3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,0.0003,0.017,-0.00058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.1e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,2.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0059,0.00031,0.017,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.1e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,2.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,0.00032,0.017,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7.1e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.8e-07,6.8e-07,2.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +23890000,0.98,-0.014,-0.021,0.18,0.053,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,0.00032,0.017,-0.00061,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,2.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.13,-0.089,-3.6,-0.0014,-0.0058,0.00032,0.018,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,2.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24090000,0.98,-0.016,-0.023,0.18,0.061,-0.066,0.09,0.13,-0.096,-3.6,-0.0014,-0.0058,0.00031,0.018,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,2.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24190000,0.98,-0.013,-0.019,0.18,0.072,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,2.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-07,6.3e-07,2.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00034,0.019,-0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,2.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00036,0.019,-0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,2.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00036,0.019,-0.0034,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,2.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24690000,0.98,-0.011,-0.014,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,0.00035,0.019,-0.0034,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,2.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.004,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,2.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.004,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,2.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.0046,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,2.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.0047,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.6e-05,6.6e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,2.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00035,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.6e-05,6.6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,2.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0052,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.6e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,2.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00033,0.018,-0.0058,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-07,5.1e-07,2.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0059,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-07,5.1e-07,2.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25590000,0.98,-0.011,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,0.00031,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,2.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00031,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,0.0003,0.018,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-07,4.8e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25890000,0.98,-0.011,-0.011,0.19,-0.0036,-0.029,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-07,4.8e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +25990000,0.98,-0.011,-0.011,0.19,-0.012,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0073,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26290000,0.98,-0.01,-0.012,0.18,-0.025,-0.014,0.00052,0.15,-0.083,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0073,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26390000,0.98,-0.0098,-0.012,0.18,-0.031,-0.0065,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0076,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0034,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00025,0.019,-0.0076,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0046,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,0.00023,0.019,-0.0078,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0097,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0078,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.2e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26890000,0.98,-0.008,-0.011,0.18,-0.051,0.016,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-07,4.2e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.035,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27290000,0.98,-0.0075,-0.013,0.18,-0.073,0.041,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27390000,0.98,-0.0089,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,0.00017,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.03,-3.5,-0.0016,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,6e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,0.00015,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,6e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27690000,0.98,-0.0089,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.049,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27890000,0.98,-0.0072,-0.012,0.18,-0.078,0.057,0.79,0.018,-0.012,-3.2,-0.0016,-0.0058,0.00014,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,0.00014,0.02,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0048,-3,-0.0016,-0.0058,0.00015,0.02,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0022,-0.0044,-3,-0.0016,-0.0058,0.00014,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0014,-2.9,-0.0016,-0.0058,0.00015,0.02,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0043,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28590000,0.98,-0.0072,-0.014,0.18,-0.083,0.06,0.79,-0.027,0.0084,-2.7,-0.0015,-0.0058,0.00015,0.02,-0.0078,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.7e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-07,3.5e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28690000,0.98,-0.007,-0.013,0.18,-0.083,0.061,0.79,-0.036,0.014,-2.6,-0.0015,-0.0058,0.00014,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.5e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28890000,0.98,-0.0062,-0.012,0.18,-0.083,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.045,0.022,-2.4,-0.0015,-0.0058,0.00015,0.02,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,0.00015,0.02,-0.0082,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29290000,0.98,-0.006,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.033,-2.2,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,0.00016,0.02,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,0.00017,0.02,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29690000,0.98,-0.0064,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29790000,0.98,-0.0063,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.043,-1.8,-0.0014,-0.0058,0.00019,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29890000,0.98,-0.0057,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,0.0002,0.02,-0.0094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,0.0002,0.021,-0.0098,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30090000,0.98,-0.006,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,0.00019,0.021,-0.0099,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.4e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,0.00017,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30290000,0.98,-0.006,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,0.00018,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.4e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30390000,0.98,-0.006,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30490000,0.98,-0.006,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,0.0002,0.022,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30690000,0.98,-0.0067,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,0.0002,0.022,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.014,0.008,0.041,0.041,0.035,3e-07,3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30790000,0.98,-0.0064,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,0.00019,0.023,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31090000,0.98,-0.0061,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,0.00019,0.023,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31190000,0.98,-0.0063,-0.013,0.19,-0.031,0.021,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,0.00021,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31390000,0.98,-0.0063,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31590000,0.98,-0.0059,-0.014,0.18,-0.018,0.0068,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,0.00021,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31690000,0.98,-0.0059,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,0.00022,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31790000,0.98,-0.0061,-0.015,0.18,-0.011,0.0032,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,0.00022,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00086,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00023,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31990000,0.98,-0.0061,-0.015,0.18,-0.00013,0.00021,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,0.00022,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32090000,0.98,-0.0065,-0.014,0.18,-0.00067,-0.0032,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00022,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32190000,0.98,-0.0067,-0.015,0.18,0.0046,-0.0064,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00022,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0091,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00023,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32390000,0.98,-0.0067,-0.015,0.18,0.012,-0.01,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-07,2.7e-07,9.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,9.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.074,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.7e-05,5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-07,2.7e-07,9.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-07,2.7e-07,9.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0057,0.00023,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.6e-05,7.5e-05,5e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32890000,0.98,-0.0091,-0.013,0.18,0.033,-0.083,-0.13,0.038,0.0021,-0.011,-0.0014,-0.0057,0.00023,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.6e-05,7.5e-05,4.9e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.001,-0.024,-0.0014,-0.0056,0.00024,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.2e-05,7.1e-05,4.9e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,9.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0091,-0.031,-0.0014,-0.0056,0.00024,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.2e-05,7.1e-05,4.9e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,9.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6.6e-05,6.6e-05,4.9e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-07,2.6e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6.7e-05,6.6e-05,4.9e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-07,2.6e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6e-05,5.9e-05,4.9e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6e-05,5.9e-05,4.9e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-07,2.6e-07,9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,0.00025,0.025,-0.018,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,5.3e-05,5.2e-05,4.8e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,8.9e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33690000,0.98,-0.0077,-0.013,0.18,0.00081,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00025,0.025,-0.018,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,5.3e-05,5.2e-05,4.8e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,8.8e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.048,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,0.00024,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.6e-05,4.6e-05,4.8e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,8.7e-07,0.025,0.026,0.0005,0,0,0,0,0,0,0,0 +33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.046,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,0.00025,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.7e-05,4.6e-05,4.8e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,8.7e-07,0.025,0.026,0.0005,0,0,0,0,0,0,0,0 +33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.1e-05,4.1e-05,4.8e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,8.6e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.1e-05,4.1e-05,4.8e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,8.5e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.021,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.7e-05,3.6e-05,4.8e-05,0.047,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,8.5e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.7e-05,3.6e-05,4.7e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,8.4e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.072,-0.01,-0.11,-0.0014,-0.0056,0.00024,0.018,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.3e-05,3.3e-05,4.7e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,8.3e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0096,-0.09,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00024,0.017,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.3e-05,3.3e-05,4.7e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,8.3e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34590000,0.98,-0.0068,-0.013,0.18,-0.014,-0.0053,0.71,0.073,-0.0089,-0.081,-0.0014,-0.0056,0.00024,0.016,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.1e-05,3.1e-05,4.7e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-07,2.6e-07,8.2e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0032,1.7,0.071,-0.0093,0.038,-0.0014,-0.0056,0.00023,0.016,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.1e-05,3.1e-05,4.7e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-07,2.6e-07,8.1e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0014,2.7,0.072,-0.0069,0.21,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00017,2.9e-05,2.9e-05,4.7e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-07,2.6e-07,8.1e-07,0.02,0.02,0.0005,0,0,0,0,0,0,0,0 +34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0038,3.6,0.07,-0.0065,0.5,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00017,2.9e-05,2.9e-05,4.7e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-07,2.6e-07,8e-07,0.02,0.02,0.0005,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index 5693c99f96..e7087115ed 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -288,11 +288,6 @@ int EkfWrapper::getQuaternionResetCounter() const return static_cast(counter); } -matrix::Vector3f EkfWrapper::getDeltaVelBiasVariance() const -{ - return _ekf->covariances_diagonal().slice<3, 1>(13, 0); -} - void EkfWrapper::enableDragFusion() { _ekf_params->drag_ctrl = 1; diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h index 6adfc5ce9a..3efaef54d2 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h @@ -120,8 +120,6 @@ public: matrix::Vector4f getQuaternionVariance() const; int getQuaternionResetCounter() const; - matrix::Vector3f getDeltaVelBiasVariance() const; - void enableDragFusion(); void disableDragFusion(); void setDragFusionParameters(const float &bcoef_x, const float &bcoef_y, const float &mcoef); diff --git a/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp b/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp index 9d4ac39012..114a051e18 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed_fusion_generated.cpp @@ -62,7 +62,7 @@ TEST(AirspeedFusionGenerated, SympyVsSymforce) // Intermediate variables const float HK0 = vn - vwn; const float HK1 = ve - vwe; - const float HK2 = ecl::powf(HK0, 2) + ecl::powf(HK1, 2) + ecl::powf(vd, 2); + const float HK2 = powf(HK0, 2.f) + powf(HK1, 2.f) + powf(vd, 2.f); const float v_tas_pred = sqrtf(HK2); // predicted airspeed //const float HK3 = powf(HK2, -1.0F/2.0F); // calculation can be badly conditioned for very low airspeed values so don't fuse this time diff --git a/src/modules/ekf2/test/test_EKF_covariance_prediction_generated.cpp b/src/modules/ekf2/test/test_EKF_covariance_prediction_generated.cpp deleted file mode 100644 index 2cc0dcf7d0..0000000000 --- a/src/modules/ekf2/test/test_EKF_covariance_prediction_generated.cpp +++ /dev/null @@ -1,816 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2022 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 - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -#include -#include "EKF/ekf.h" -#include "test_helper/comparison_helper.h" - -#include "../EKF/python/ekf_derivation/generated/predict_covariance.h" - -using namespace matrix; - -TEST(CovariancePredictionGenerated, SympyVsSymforce) -{ - // Compare calculation of observation Jacobians and Kalman gains for sympy and symforce generated equations - const Quatf q(Eulerf(-M_PI_F / 2.f, M_PI_F / 3.f, M_PI_F * 4.f / 5.f)); - const float q0 = q(0); - const float q1 = q(1); - const float q2 = q(2); - const float q3 = q(3); - - const float dt = 0.01f; - - // up to 1 rad/sec of rate - const float dax = 2.0f * dt * ((float)randf() - 0.5f); - const float day = 2.0f * dt * ((float)randf() - 0.5f); - const float daz = 2.0f * dt * ((float)randf() - 0.5f); - - // up to 2g of accel - const float dvx = 2.0f * 20.0f * dt * ((float)randf() - 0.5f); - const float dvy = 2.0f * 20.0f * dt * ((float)randf() - 0.5f); - const float dvz = 2.0f * 20.0f * dt * ((float)randf() - 0.5f); - - // up to 0.1 rad/sec of gyro bias - const float dax_b = 2.0f * 0.1f * dt * ((float)randf() - 0.5f); - const float day_b = 2.0f * 0.1f * dt * ((float)randf() - 0.5f); - const float daz_b = 2.0f * 0.1f * dt * ((float)randf() - 0.5f); - - // up to 0.5 m/s/s of accel bias - const float dvx_b = 2.0f * 0.5f * dt * ((float)randf() - 0.5f); - const float dvy_b = 2.0f * 0.5f * dt * ((float)randf() - 0.5f); - const float dvz_b = 2.0f * 0.5f * dt * ((float)randf() - 0.5f); - - const float daxVar = sq(dt * 0.015f); - const float dayVar = daxVar; - const float dazVar = daxVar; - - const float dvxVar = sq(dt * 0.3f); - const float dvyVar = dvxVar; - const float dvzVar = dvxVar; - - SquareMatrix24f P = createRandomCovarianceMatrix24f(); - SquareMatrix24f nextP_sympy; - SquareMatrix24f nextP_symforce; - - { - SquareMatrix24f nextP; - // Equations for covariance matrix prediction, without process noise! - const float PS0 = (q1) * (q1); - const float PS1 = 0.25F * daxVar; - const float PS2 = (q2) * (q2); - const float PS3 = 0.25F * dayVar; - const float PS4 = (q3) * (q3); - const float PS5 = 0.25F * dazVar; - const float PS6 = 0.5F * q1; - const float PS7 = 0.5F * q2; - const float PS8 = P(10, 11) * PS7; - const float PS9 = 0.5F * q3; - const float PS10 = P(10, 12) * PS9; - const float PS11 = 0.5F * dax - 0.5F * dax_b; - const float PS12 = 0.5F * day - 0.5F * day_b; - const float PS13 = 0.5F * daz - 0.5F * daz_b; - const float PS14 = P(0, 10) - P(1, 10) * PS11 + P(10, 10) * PS6 - P(2, 10) * PS12 - P(3, 10) * PS13 + PS10 + PS8; - const float PS15 = P(10, 11) * PS6; - const float PS16 = P(11, 12) * PS9; - const float PS17 = P(0, 11) - P(1, 11) * PS11 + P(11, 11) * PS7 - P(2, 11) * PS12 - P(3, 11) * PS13 + PS15 + PS16; - const float PS18 = P(10, 12) * PS6; - const float PS19 = P(11, 12) * PS7; - const float PS20 = P(0, 12) - P(1, 12) * PS11 + P(12, 12) * PS9 - P(2, 12) * PS12 - P(3, 12) * PS13 + PS18 + PS19; - const float PS21 = P(1, 2) * PS12; - const float PS22 = -P(1, 3) * PS13; - const float PS23 = P(0, 1) - P(1, 1) * PS11 + P(1, 10) * PS6 + P(1, 11) * PS7 + P(1, 12) * PS9 - PS21 + PS22; - const float PS24 = -P(1, 2) * PS11; - const float PS25 = P(2, 3) * PS13; - const float PS26 = P(0, 2) + P(2, 10) * PS6 + P(2, 11) * PS7 + P(2, 12) * PS9 - P(2, 2) * PS12 + PS24 - PS25; - const float PS27 = P(1, 3) * PS11; - const float PS28 = -P(2, 3) * PS12; - const float PS29 = P(0, 3) + P(3, 10) * PS6 + P(3, 11) * PS7 + P(3, 12) * PS9 - P(3, 3) * PS13 - PS27 + PS28; - const float PS30 = P(0, 1) * PS11; - const float PS31 = P(0, 2) * PS12; - const float PS32 = P(0, 3) * PS13; - const float PS33 = P(0, 0) + P(0, 10) * PS6 + P(0, 11) * PS7 + P(0, 12) * PS9 - PS30 - PS31 - PS32; - const float PS34 = 0.5F * q0; - const float PS35 = q2 * q3; - const float PS36 = q0 * q1; - const float PS37 = q1 * q3; - const float PS38 = q0 * q2; - const float PS39 = q1 * q2; - const float PS40 = q0 * q3; - const float PS41 = 2 * PS2; - const float PS42 = 2 * PS4 - 1; - const float PS43 = PS41 + PS42; - const float PS44 = P(0, 13) - P(1, 13) * PS11 + P(10, 13) * PS6 + P(11, 13) * PS7 + P(12, 13) * PS9 - P(2, - 13) * PS12 - P(3, 13) * PS13; - const float PS45 = PS37 + PS38; - const float PS46 = P(0, 15) - P(1, 15) * PS11 + P(10, 15) * PS6 + P(11, 15) * PS7 + P(12, 15) * PS9 - P(2, - 15) * PS12 - P(3, 15) * PS13; - const float PS47 = 2 * PS46; - const float PS48 = dvy - dvy_b; - const float PS49 = PS48 * q0; - const float PS50 = dvz - dvz_b; - const float PS51 = PS50 * q1; - const float PS52 = dvx - dvx_b; - const float PS53 = PS52 * q3; - const float PS54 = PS49 - PS51 + 2 * PS53; - const float PS55 = 2 * PS29; - const float PS56 = -PS39 + PS40; - const float PS57 = P(0, 14) - P(1, 14) * PS11 + P(10, 14) * PS6 + P(11, 14) * PS7 + P(12, 14) * PS9 - P(2, - 14) * PS12 - P(3, 14) * PS13; - const float PS58 = 2 * PS57; - const float PS59 = PS48 * q2; - const float PS60 = PS50 * q3; - const float PS61 = PS59 + PS60; - const float PS62 = 2 * PS23; - const float PS63 = PS50 * q2; - const float PS64 = PS48 * q3; - const float PS65 = -PS64; - const float PS66 = PS63 + PS65; - const float PS67 = 2 * PS33; - const float PS68 = PS50 * q0; - const float PS69 = PS48 * q1; - const float PS70 = PS52 * q2; - const float PS71 = PS68 + PS69 - 2 * PS70; - const float PS72 = 2 * PS26; - const float PS73 = P(0, 4) - P(1, 4) * PS11 - P(2, 4) * PS12 - P(3, 4) * PS13 + P(4, 10) * PS6 + P(4, 11) * PS7 + P(4, - 12) * PS9; - const float PS74 = 2 * PS0; - const float PS75 = PS42 + PS74; - const float PS76 = PS39 + PS40; - const float PS77 = 2 * PS44; - const float PS78 = PS51 - PS53; - const float PS79 = -PS70; - const float PS80 = PS68 + 2 * PS69 + PS79; - const float PS81 = -PS35 + PS36; - const float PS82 = PS52 * q1; - const float PS83 = PS60 + PS82; - const float PS84 = PS52 * q0; - const float PS85 = PS63 - 2 * PS64 + PS84; - const float PS86 = P(0, 5) - P(1, 5) * PS11 - P(2, 5) * PS12 - P(3, 5) * PS13 + P(5, 10) * PS6 + P(5, 11) * PS7 + P(5, - 12) * PS9; - const float PS87 = PS41 + PS74 - 1; - const float PS88 = PS35 + PS36; - const float PS89 = 2 * PS63 + PS65 + PS84; - const float PS90 = -PS37 + PS38; - const float PS91 = PS59 + PS82; - const float PS92 = PS69 + PS79; - const float PS93 = PS49 - 2 * PS51 + PS53; - const float PS94 = P(0, 6) - P(1, 6) * PS11 - P(2, 6) * PS12 - P(3, 6) * PS13 + P(6, 10) * PS6 + P(6, 11) * PS7 + P(6, - 12) * PS9; - const float PS95 = (q0) * (q0); - const float PS96 = -P(10, 11) * PS34; - const float PS97 = P(0, 11) * PS11 + P(1, 11) + P(11, 11) * PS9 + P(2, 11) * PS13 - P(3, 11) * PS12 - PS19 + PS96; - const float PS98 = P(0, 2) * PS13; - const float PS99 = P(0, 3) * PS12; - const float PS100 = P(0, 0) * PS11 + P(0, 1) - P(0, 10) * PS34 + P(0, 11) * PS9 - P(0, 12) * PS7 + PS98 - PS99; - const float PS101 = P(0, 2) * PS11; - const float PS102 = P(1, 2) - P(2, 10) * PS34 + P(2, 11) * PS9 - P(2, 12) * PS7 + P(2, 2) * PS13 + PS101 + PS28; - const float PS103 = P(10, 11) * PS9; - const float PS104 = P(10, 12) * PS7; - const float PS105 = P(0, 10) * PS11 + P(1, 10) - P(10, 10) * PS34 + P(2, 10) * PS13 - P(3, 10) * PS12 + PS103 - PS104; - const float PS106 = -P(10, 12) * PS34; - const float PS107 = P(0, 12) * PS11 + P(1, 12) - P(12, 12) * PS7 + P(2, 12) * PS13 - P(3, 12) * PS12 + PS106 + PS16; - const float PS108 = P(0, 3) * PS11; - const float PS109 = P(1, 3) - P(3, 10) * PS34 + P(3, 11) * PS9 - P(3, 12) * PS7 - P(3, 3) * PS12 + PS108 + PS25; - const float PS110 = P(1, 2) * PS13; - const float PS111 = P(1, 3) * PS12; - const float PS112 = P(1, 1) - P(1, 10) * PS34 + P(1, 11) * PS9 - P(1, 12) * PS7 + PS110 - PS111 + PS30; - const float PS113 = P(0, 13) * PS11 + P(1, 13) - P(10, 13) * PS34 + P(11, 13) * PS9 - P(12, 13) * PS7 + P(2, - 13) * PS13 - P(3, 13) * PS12; - const float PS114 = P(0, 15) * PS11 + P(1, 15) - P(10, 15) * PS34 + P(11, 15) * PS9 - P(12, 15) * PS7 + P(2, - 15) * PS13 - P(3, 15) * PS12; - const float PS115 = 2 * PS114; - const float PS116 = 2 * PS109; - const float PS117 = P(0, 14) * PS11 + P(1, 14) - P(10, 14) * PS34 + P(11, 14) * PS9 - P(12, 14) * PS7 + P(2, - 14) * PS13 - P(3, 14) * PS12; - const float PS118 = 2 * PS117; - const float PS119 = 2 * PS112; - const float PS120 = 2 * PS100; - const float PS121 = 2 * PS102; - const float PS122 = P(0, 4) * PS11 + P(1, 4) + P(2, 4) * PS13 - P(3, 4) * PS12 - P(4, 10) * PS34 + P(4, 11) * PS9 - P(4, - 12) * PS7; - const float PS123 = 2 * PS113; - const float PS124 = P(0, 5) * PS11 + P(1, 5) + P(2, 5) * PS13 - P(3, 5) * PS12 - P(5, 10) * PS34 + P(5, 11) * PS9 - P(5, - 12) * PS7; - const float PS125 = P(0, 6) * PS11 + P(1, 6) + P(2, 6) * PS13 - P(3, 6) * PS12 - P(6, 10) * PS34 + P(6, 11) * PS9 - P(6, - 12) * PS7; - const float PS126 = -P(11, 12) * PS34; - const float PS127 = P(0, 12) * PS12 - P(1, 12) * PS13 + P(12, 12) * PS6 + P(2, 12) + P(3, 12) * PS11 - PS10 + PS126; - const float PS128 = P(2, 3) - P(3, 10) * PS9 - P(3, 11) * PS34 + P(3, 12) * PS6 + P(3, 3) * PS11 + PS22 + PS99; - const float PS129 = P(0, 1) * PS13; - const float PS130 = P(0, 0) * PS12 - P(0, 10) * PS9 - P(0, 11) * PS34 + P(0, 12) * PS6 + P(0, 2) + PS108 - PS129; - const float PS131 = P(11, 12) * PS6; - const float PS132 = P(0, 11) * PS12 - P(1, 11) * PS13 - P(11, 11) * PS34 + P(2, 11) + P(3, 11) * PS11 - PS103 + PS131; - const float PS133 = P(0, 10) * PS12 - P(1, 10) * PS13 - P(10, 10) * PS9 + P(2, 10) + P(3, 10) * PS11 + PS18 + PS96; - const float PS134 = P(0, 1) * PS12; - const float PS135 = -P(1, 1) * PS13 - P(1, 10) * PS9 - P(1, 11) * PS34 + P(1, 12) * PS6 + P(1, 2) + PS134 + PS27; - const float PS136 = P(2, 3) * PS11; - const float PS137 = -P(2, 10) * PS9 - P(2, 11) * PS34 + P(2, 12) * PS6 + P(2, 2) - PS110 + PS136 + PS31; - const float PS138 = P(0, 13) * PS12 - P(1, 13) * PS13 - P(10, 13) * PS9 - P(11, 13) * PS34 + P(12, 13) * PS6 + P(2, - 13) + P(3, 13) * PS11; - const float PS139 = P(0, 15) * PS12 - P(1, 15) * PS13 - P(10, 15) * PS9 - P(11, 15) * PS34 + P(12, 15) * PS6 + P(2, - 15) + P(3, 15) * PS11; - const float PS140 = 2 * PS139; - const float PS141 = 2 * PS128; - const float PS142 = P(0, 14) * PS12 - P(1, 14) * PS13 - P(10, 14) * PS9 - P(11, 14) * PS34 + P(12, 14) * PS6 + P(2, - 14) + P(3, 14) * PS11; - const float PS143 = 2 * PS142; - const float PS144 = 2 * PS135; - const float PS145 = 2 * PS130; - const float PS146 = 2 * PS137; - const float PS147 = P(0, 4) * PS12 - P(1, 4) * PS13 + P(2, 4) + P(3, 4) * PS11 - P(4, 10) * PS9 - P(4, 11) * PS34 + P(4, - 12) * PS6; - const float PS148 = 2 * PS138; - const float PS149 = P(0, 5) * PS12 - P(1, 5) * PS13 + P(2, 5) + P(3, 5) * PS11 - P(5, 10) * PS9 - P(5, 11) * PS34 + P(5, - 12) * PS6; - const float PS150 = P(0, 6) * PS12 - P(1, 6) * PS13 + P(2, 6) + P(3, 6) * PS11 - P(6, 10) * PS9 - P(6, 11) * PS34 + P(6, - 12) * PS6; - const float PS151 = P(0, 10) * PS13 + P(1, 10) * PS12 + P(10, 10) * PS7 - P(2, 10) * PS11 + P(3, 10) + PS106 - PS15; - const float PS152 = P(1, 1) * PS12 + P(1, 10) * PS7 - P(1, 11) * PS6 - P(1, 12) * PS34 + P(1, 3) + PS129 + PS24; - const float PS153 = P(0, 0) * PS13 + P(0, 10) * PS7 - P(0, 11) * PS6 - P(0, 12) * PS34 + P(0, 3) - PS101 + PS134; - const float PS154 = P(0, 12) * PS13 + P(1, 12) * PS12 - P(12, 12) * PS34 - P(2, 12) * PS11 + P(3, 12) + PS104 - PS131; - const float PS155 = P(0, 11) * PS13 + P(1, 11) * PS12 - P(11, 11) * PS6 - P(2, 11) * PS11 + P(3, 11) + PS126 + PS8; - const float PS156 = P(2, 10) * PS7 - P(2, 11) * PS6 - P(2, 12) * PS34 - P(2, 2) * PS11 + P(2, 3) + PS21 + PS98; - const float PS157 = P(3, 10) * PS7 - P(3, 11) * PS6 - P(3, 12) * PS34 + P(3, 3) + PS111 - PS136 + PS32; - const float PS158 = P(0, 13) * PS13 + P(1, 13) * PS12 + P(10, 13) * PS7 - P(11, 13) * PS6 - P(12, 13) * PS34 - P(2, - 13) * PS11 + P(3, 13); - const float PS159 = P(0, 15) * PS13 + P(1, 15) * PS12 + P(10, 15) * PS7 - P(11, 15) * PS6 - P(12, 15) * PS34 - P(2, - 15) * PS11 + P(3, 15); - const float PS160 = 2 * PS159; - const float PS161 = 2 * PS157; - const float PS162 = P(0, 14) * PS13 + P(1, 14) * PS12 + P(10, 14) * PS7 - P(11, 14) * PS6 - P(12, 14) * PS34 - P(2, - 14) * PS11 + P(3, 14); - const float PS163 = 2 * PS162; - const float PS164 = 2 * PS152; - const float PS165 = 2 * PS153; - const float PS166 = 2 * PS156; - const float PS167 = P(0, 4) * PS13 + P(1, 4) * PS12 - P(2, 4) * PS11 + P(3, 4) + P(4, 10) * PS7 - P(4, 11) * PS6 - P(4, - 12) * PS34; - const float PS168 = 2 * PS158; - const float PS169 = P(0, 5) * PS13 + P(1, 5) * PS12 - P(2, 5) * PS11 + P(3, 5) + P(5, 10) * PS7 - P(5, 11) * PS6 - P(5, - 12) * PS34; - const float PS170 = P(0, 6) * PS13 + P(1, 6) * PS12 - P(2, 6) * PS11 + P(3, 6) + P(6, 10) * PS7 - P(6, 11) * PS6 - P(6, - 12) * PS34; - const float PS171 = 2 * PS45; - const float PS172 = 2 * PS56; - const float PS173 = 2 * PS61; - const float PS174 = 2 * PS66; - const float PS175 = 2 * PS71; - const float PS176 = 2 * PS54; - const float PS177 = P(0, 13) * PS174 + P(1, 13) * PS173 + P(13, 13) * PS43 + P(13, 14) * PS172 - P(13, - 15) * PS171 + P(2, 13) * PS175 - P(3, 13) * PS176 + P(4, 13); - const float PS178 = P(0, 15) * PS174 + P(1, 15) * PS173 + P(13, 15) * PS43 + P(14, 15) * PS172 - P(15, - 15) * PS171 + P(2, 15) * PS175 - P(3, 15) * PS176 + P(4, 15); - const float PS179 = P(0, 3) * PS174 + P(1, 3) * PS173 + P(2, 3) * PS175 + P(3, 13) * PS43 + P(3, 14) * PS172 - P(3, - 15) * PS171 - P(3, 3) * PS176 + P(3, 4); - const float PS180 = P(0, 14) * PS174 + P(1, 14) * PS173 + P(13, 14) * PS43 + P(14, 14) * PS172 - P(14, - 15) * PS171 + P(2, 14) * PS175 - P(3, 14) * PS176 + P(4, 14); - const float PS181 = P(0, 1) * PS174 + P(1, 1) * PS173 + P(1, 13) * PS43 + P(1, 14) * PS172 - P(1, 15) * PS171 + P(1, - 2) * PS175 - P(1, 3) * PS176 + P(1, 4); - const float PS182 = P(0, 0) * PS174 + P(0, 1) * PS173 + P(0, 13) * PS43 + P(0, 14) * PS172 - P(0, 15) * PS171 + P(0, - 2) * PS175 - P(0, 3) * PS176 + P(0, 4); - const float PS183 = P(0, 2) * PS174 + P(1, 2) * PS173 + P(2, 13) * PS43 + P(2, 14) * PS172 - P(2, 15) * PS171 + P(2, - 2) * PS175 - P(2, 3) * PS176 + P(2, 4); - const float PS184 = 4 * dvyVar; - const float PS185 = 4 * dvzVar; - const float PS186 = P(0, 4) * PS174 + P(1, 4) * PS173 + P(2, 4) * PS175 - P(3, 4) * PS176 + P(4, 13) * PS43 + P(4, - 14) * PS172 - P(4, 15) * PS171 + P(4, 4); - const float PS187 = 2 * PS177; - const float PS188 = 2 * PS182; - const float PS189 = 2 * PS181; - const float PS190 = 2 * PS81; - const float PS191 = 2 * PS183; - const float PS192 = 2 * PS179; - const float PS193 = 2 * PS76; - const float PS194 = PS43 * dvxVar; - const float PS195 = PS75 * dvyVar; - const float PS196 = P(0, 5) * PS174 + P(1, 5) * PS173 + P(2, 5) * PS175 - P(3, 5) * PS176 + P(4, 5) + P(5, - 13) * PS43 + P(5, 14) * PS172 - P(5, 15) * PS171; - const float PS197 = 2 * PS88; - const float PS198 = PS87 * dvzVar; - const float PS199 = 2 * PS90; - const float PS200 = P(0, 6) * PS174 + P(1, 6) * PS173 + P(2, 6) * PS175 - P(3, 6) * PS176 + P(4, 6) + P(6, - 13) * PS43 + P(6, 14) * PS172 - P(6, 15) * PS171; - const float PS201 = 2 * PS83; - const float PS202 = 2 * PS78; - const float PS203 = 2 * PS85; - const float PS204 = 2 * PS80; - const float PS205 = -P(0, 14) * PS202 - P(1, 14) * PS204 - P(13, 14) * PS193 + P(14, 14) * PS75 + P(14, - 15) * PS190 + P(2, 14) * PS201 + P(3, 14) * PS203 + P(5, 14); - const float PS206 = -P(0, 13) * PS202 - P(1, 13) * PS204 - P(13, 13) * PS193 + P(13, 14) * PS75 + P(13, - 15) * PS190 + P(2, 13) * PS201 + P(3, 13) * PS203 + P(5, 13); - const float PS207 = -P(0, 0) * PS202 - P(0, 1) * PS204 - P(0, 13) * PS193 + P(0, 14) * PS75 + P(0, 15) * PS190 + P(0, - 2) * PS201 + P(0, 3) * PS203 + P(0, 5); - const float PS208 = -P(0, 1) * PS202 - P(1, 1) * PS204 - P(1, 13) * PS193 + P(1, 14) * PS75 + P(1, 15) * PS190 + P(1, - 2) * PS201 + P(1, 3) * PS203 + P(1, 5); - const float PS209 = -P(0, 15) * PS202 - P(1, 15) * PS204 - P(13, 15) * PS193 + P(14, 15) * PS75 + P(15, - 15) * PS190 + P(2, 15) * PS201 + P(3, 15) * PS203 + P(5, 15); - const float PS210 = -P(0, 2) * PS202 - P(1, 2) * PS204 - P(2, 13) * PS193 + P(2, 14) * PS75 + P(2, 15) * PS190 + P(2, - 2) * PS201 + P(2, 3) * PS203 + P(2, 5); - const float PS211 = -P(0, 3) * PS202 - P(1, 3) * PS204 + P(2, 3) * PS201 - P(3, 13) * PS193 + P(3, 14) * PS75 + P(3, - 15) * PS190 + P(3, 3) * PS203 + P(3, 5); - const float PS212 = 4 * dvxVar; - const float PS213 = -P(0, 5) * PS202 - P(1, 5) * PS204 + P(2, 5) * PS201 + P(3, 5) * PS203 - P(5, 13) * PS193 + P(5, - 14) * PS75 + P(5, 15) * PS190 + P(5, 5); - const float PS214 = 2 * PS89; - const float PS215 = 2 * PS91; - const float PS216 = 2 * PS92; - const float PS217 = 2 * PS93; - const float PS218 = -P(0, 6) * PS202 - P(1, 6) * PS204 + P(2, 6) * PS201 + P(3, 6) * PS203 + P(5, 6) - P(6, - 13) * PS193 + P(6, 14) * PS75 + P(6, 15) * PS190; - const float PS219 = P(0, 15) * PS216 + P(1, 15) * PS217 + P(13, 15) * PS199 - P(14, 15) * PS197 + P(15, - 15) * PS87 - P(2, 15) * PS214 + P(3, 15) * PS215 + P(6, 15); - const float PS220 = P(0, 14) * PS216 + P(1, 14) * PS217 + P(13, 14) * PS199 - P(14, 14) * PS197 + P(14, - 15) * PS87 - P(2, 14) * PS214 + P(3, 14) * PS215 + P(6, 14); - const float PS221 = P(0, 13) * PS216 + P(1, 13) * PS217 + P(13, 13) * PS199 - P(13, 14) * PS197 + P(13, - 15) * PS87 - P(2, 13) * PS214 + P(3, 13) * PS215 + P(6, 13); - const float PS222 = P(0, 6) * PS216 + P(1, 6) * PS217 - P(2, 6) * PS214 + P(3, 6) * PS215 + P(6, 13) * PS199 - P(6, - 14) * PS197 + P(6, 15) * PS87 + P(6, 6); - - - nextP(0, 0) = PS0 * PS1 - PS11 * PS23 - PS12 * PS26 - PS13 * PS29 + PS14 * PS6 + PS17 * PS7 + PS2 * PS3 + PS20 * PS9 + - PS33 + PS4 * PS5; - nextP(0, 1) = -PS1 * PS36 + PS11 * PS33 - PS12 * PS29 + PS13 * PS26 - PS14 * PS34 + PS17 * PS9 - PS20 * PS7 + PS23 + PS3 - * PS35 - PS35 * PS5; - nextP(1, 1) = PS1 * PS95 + PS100 * PS11 + PS102 * PS13 - PS105 * PS34 - PS107 * PS7 - PS109 * PS12 + PS112 + PS2 * PS5 + - PS3 * PS4 + PS9 * PS97; - nextP(0, 2) = -PS1 * PS37 + PS11 * PS29 + PS12 * PS33 - PS13 * PS23 - PS14 * PS9 - PS17 * PS34 + PS20 * PS6 + PS26 - PS3 - * PS38 + PS37 * PS5; - nextP(1, 2) = PS1 * PS40 + PS100 * PS12 + PS102 - PS105 * PS9 + PS107 * PS6 + PS109 * PS11 - PS112 * PS13 - PS3 * PS40 - - PS34 * PS97 - PS39 * PS5; - nextP(2, 2) = PS0 * PS5 + PS1 * PS4 + PS11 * PS128 + PS12 * PS130 + PS127 * PS6 - PS13 * PS135 - PS132 * PS34 - PS133 * - PS9 + PS137 + PS3 * PS95; - nextP(0, 3) = PS1 * PS39 - PS11 * PS26 + PS12 * PS23 + PS13 * PS33 + PS14 * PS7 - PS17 * PS6 - PS20 * PS34 + PS29 - PS3 - * PS39 - PS40 * PS5; - nextP(1, 3) = -PS1 * PS38 + PS100 * PS13 - PS102 * PS11 + PS105 * PS7 - PS107 * PS34 + PS109 + PS112 * PS12 - PS3 * PS37 - + PS38 * PS5 - PS6 * PS97; - nextP(2, 3) = -PS1 * PS35 - PS11 * PS137 + PS12 * PS135 - PS127 * PS34 + PS128 + PS13 * PS130 - PS132 * PS6 + PS133 * - PS7 + PS3 * PS36 - PS36 * PS5; - nextP(3, 3) = PS0 * PS3 + PS1 * PS2 - PS11 * PS156 + PS12 * PS152 + PS13 * PS153 + PS151 * PS7 - PS154 * PS34 - PS155 * - PS6 + PS157 + PS5 * PS95; - nextP(0, 4) = PS43 * PS44 - PS45 * PS47 - PS54 * PS55 + PS56 * PS58 + PS61 * PS62 + PS66 * PS67 + PS71 * PS72 + PS73; - nextP(1, 4) = PS113 * PS43 - PS115 * PS45 - PS116 * PS54 + PS118 * PS56 + PS119 * PS61 + PS120 * PS66 + PS121 * PS71 + - PS122; - nextP(2, 4) = PS138 * PS43 - PS140 * PS45 - PS141 * PS54 + PS143 * PS56 + PS144 * PS61 + PS145 * PS66 + PS146 * PS71 + - PS147; - nextP(3, 4) = PS158 * PS43 - PS160 * PS45 - PS161 * PS54 + PS163 * PS56 + PS164 * PS61 + PS165 * PS66 + PS166 * PS71 + - PS167; - nextP(4, 4) = -PS171 * PS178 + PS172 * PS180 + PS173 * PS181 + PS174 * PS182 + PS175 * PS183 - PS176 * PS179 + PS177 * - PS43 + PS184 * (PS56) * (PS56) + PS185 * (PS45) * (PS45) + PS186 + (PS43) * (PS43) * dvxVar; - nextP(0, 5) = PS47 * PS81 + PS55 * PS85 + PS57 * PS75 - PS62 * PS80 - PS67 * PS78 + PS72 * PS83 - PS76 * PS77 + PS86; - nextP(1, 5) = PS115 * PS81 + PS116 * PS85 + PS117 * PS75 - PS119 * PS80 - PS120 * PS78 + PS121 * PS83 - PS123 * PS76 + - PS124; - nextP(2, 5) = PS140 * PS81 + PS141 * PS85 + PS142 * PS75 - PS144 * PS80 - PS145 * PS78 + PS146 * PS83 - PS148 * PS76 + - PS149; - nextP(3, 5) = PS160 * PS81 + PS161 * PS85 + PS162 * PS75 - PS164 * PS80 - PS165 * PS78 + PS166 * PS83 - PS168 * PS76 + - PS169; - nextP(4, 5) = PS172 * PS195 + PS178 * PS190 + PS180 * PS75 - PS185 * PS45 * PS81 - PS187 * PS76 - PS188 * PS78 - PS189 * - PS80 + PS191 * PS83 + PS192 * PS85 - PS193 * PS194 + PS196; - nextP(5, 5) = PS185 * (PS81) * (PS81) + PS190 * PS209 - PS193 * PS206 + PS201 * PS210 - PS202 * PS207 + PS203 * PS211 - - PS204 * PS208 + PS205 * PS75 + PS212 * (PS76) * (PS76) + PS213 + (PS75) * (PS75) * dvyVar; - nextP(0, 6) = PS46 * PS87 + PS55 * PS91 - PS58 * PS88 + PS62 * PS93 + PS67 * PS92 - PS72 * PS89 + PS77 * PS90 + PS94; - nextP(1, 6) = PS114 * PS87 + PS116 * PS91 - PS118 * PS88 + PS119 * PS93 + PS120 * PS92 - PS121 * PS89 + PS123 * PS90 + - PS125; - nextP(2, 6) = PS139 * PS87 + PS141 * PS91 - PS143 * PS88 + PS144 * PS93 + PS145 * PS92 - PS146 * PS89 + PS148 * PS90 + - PS150; - nextP(3, 6) = PS159 * PS87 + PS161 * PS91 - PS163 * PS88 + PS164 * PS93 + PS165 * PS92 - PS166 * PS89 + PS168 * PS90 + - PS170; - nextP(4, 6) = -PS171 * PS198 + PS178 * PS87 - PS180 * PS197 - PS184 * PS56 * PS88 + PS187 * PS90 + PS188 * PS92 + PS189 - * PS93 - PS191 * PS89 + PS192 * PS91 + PS194 * PS199 + PS200; - nextP(5, 6) = PS190 * PS198 - PS195 * PS197 - PS197 * PS205 + PS199 * PS206 + PS207 * PS216 + PS208 * PS217 + PS209 * - PS87 - PS210 * PS214 + PS211 * PS215 - PS212 * PS76 * PS90 + PS218; - nextP(6, 6) = PS184 * (PS88) * (PS88) - PS197 * PS220 + PS199 * PS221 + PS212 * (PS90) * (PS90) - PS214 * (P(0, - 2) * PS216 + P(1, 2) * PS217 + P(2, 13) * PS199 - P(2, 14) * PS197 + P(2, 15) * PS87 - P(2, 2) * PS214 + P(2, - 3) * PS215 + P(2, 6)) + PS215 * (P(0, 3) * PS216 + P(1, 3) * PS217 - P(2, 3) * PS214 + P(3, 13) * PS199 - P(3, - 14) * PS197 + P(3, 15) * PS87 + P(3, 3) * PS215 + P(3, 6)) + PS216 * (P(0, 0) * PS216 + P(0, 1) * PS217 + P(0, - 13) * PS199 - P(0, 14) * PS197 + P(0, 15) * PS87 - P(0, 2) * PS214 + P(0, 3) * PS215 + P(0, 6)) + PS217 * (P(0, - 1) * PS216 + P(1, 1) * PS217 + P(1, 13) * PS199 - P(1, 14) * PS197 + P(1, 15) * PS87 - P(1, 2) * PS214 + P(1, - 3) * PS215 + P(1, 6)) + PS219 * PS87 + PS222 + (PS87) * (PS87) * dvzVar; - nextP(0, 7) = P(0, 7) - P(1, 7) * PS11 - P(2, 7) * PS12 - P(3, 7) * PS13 + P(7, 10) * PS6 + P(7, 11) * PS7 + P(7, - 12) * PS9 + PS73 * dt; - nextP(1, 7) = P(0, 7) * PS11 + P(1, 7) + P(2, 7) * PS13 - P(3, 7) * PS12 - P(7, 10) * PS34 + P(7, 11) * PS9 - P(7, - 12) * PS7 + PS122 * dt; - nextP(2, 7) = P(0, 7) * PS12 - P(1, 7) * PS13 + P(2, 7) + P(3, 7) * PS11 - P(7, 10) * PS9 - P(7, 11) * PS34 + P(7, - 12) * PS6 + PS147 * dt; - nextP(3, 7) = P(0, 7) * PS13 + P(1, 7) * PS12 - P(2, 7) * PS11 + P(3, 7) + P(7, 10) * PS7 - P(7, 11) * PS6 - P(7, - 12) * PS34 + PS167 * dt; - nextP(4, 7) = P(0, 7) * PS174 + P(1, 7) * PS173 + P(2, 7) * PS175 - P(3, 7) * PS176 + P(4, 7) + P(7, 13) * PS43 + P(7, - 14) * PS172 - P(7, 15) * PS171 + PS186 * dt; - nextP(5, 7) = -P(0, 7) * PS202 - P(1, 7) * PS204 + P(2, 7) * PS201 + P(3, 7) * PS203 + P(5, 7) - P(7, 13) * PS193 + P(7, - 14) * PS75 + P(7, 15) * PS190 + dt * (-P(0, 4) * PS202 - P(1, 4) * PS204 + P(2, 4) * PS201 + P(3, 4) * PS203 - P(4, - 13) * PS193 + P(4, 14) * PS75 + P(4, 15) * PS190 + P(4, 5)); - nextP(6, 7) = P(0, 7) * PS216 + P(1, 7) * PS217 - P(2, 7) * PS214 + P(3, 7) * PS215 + P(6, 7) + P(7, 13) * PS199 - P(7, - 14) * PS197 + P(7, 15) * PS87 + dt * (P(0, 4) * PS216 + P(1, 4) * PS217 - P(2, 4) * PS214 + P(3, 4) * PS215 + P(4, - 13) * PS199 - P(4, 14) * PS197 + P(4, 15) * PS87 + P(4, 6)); - nextP(7, 7) = P(4, 7) * dt + P(7, 7) + dt * (P(4, 4) * dt + P(4, 7)); - nextP(0, 8) = P(0, 8) - P(1, 8) * PS11 - P(2, 8) * PS12 - P(3, 8) * PS13 + P(8, 10) * PS6 + P(8, 11) * PS7 + P(8, - 12) * PS9 + PS86 * dt; - nextP(1, 8) = P(0, 8) * PS11 + P(1, 8) + P(2, 8) * PS13 - P(3, 8) * PS12 - P(8, 10) * PS34 + P(8, 11) * PS9 - P(8, - 12) * PS7 + PS124 * dt; - nextP(2, 8) = P(0, 8) * PS12 - P(1, 8) * PS13 + P(2, 8) + P(3, 8) * PS11 - P(8, 10) * PS9 - P(8, 11) * PS34 + P(8, - 12) * PS6 + PS149 * dt; - nextP(3, 8) = P(0, 8) * PS13 + P(1, 8) * PS12 - P(2, 8) * PS11 + P(3, 8) + P(8, 10) * PS7 - P(8, 11) * PS6 - P(8, - 12) * PS34 + PS169 * dt; - nextP(4, 8) = P(0, 8) * PS174 + P(1, 8) * PS173 + P(2, 8) * PS175 - P(3, 8) * PS176 + P(4, 8) + P(8, 13) * PS43 + P(8, - 14) * PS172 - P(8, 15) * PS171 + PS196 * dt; - nextP(5, 8) = -P(0, 8) * PS202 - P(1, 8) * PS204 + P(2, 8) * PS201 + P(3, 8) * PS203 + P(5, 8) - P(8, 13) * PS193 + P(8, - 14) * PS75 + P(8, 15) * PS190 + PS213 * dt; - nextP(6, 8) = P(0, 8) * PS216 + P(1, 8) * PS217 - P(2, 8) * PS214 + P(3, 8) * PS215 + P(6, 8) + P(8, 13) * PS199 - P(8, - 14) * PS197 + P(8, 15) * PS87 + dt * (P(0, 5) * PS216 + P(1, 5) * PS217 - P(2, 5) * PS214 + P(3, 5) * PS215 + P(5, - 13) * PS199 - P(5, 14) * PS197 + P(5, 15) * PS87 + P(5, 6)); - nextP(7, 8) = P(4, 8) * dt + P(7, 8) + dt * (P(4, 5) * dt + P(5, 7)); - nextP(8, 8) = P(5, 8) * dt + P(8, 8) + dt * (P(5, 5) * dt + P(5, 8)); - nextP(0, 9) = P(0, 9) - P(1, 9) * PS11 - P(2, 9) * PS12 - P(3, 9) * PS13 + P(9, 10) * PS6 + P(9, 11) * PS7 + P(9, - 12) * PS9 + PS94 * dt; - nextP(1, 9) = P(0, 9) * PS11 + P(1, 9) + P(2, 9) * PS13 - P(3, 9) * PS12 - P(9, 10) * PS34 + P(9, 11) * PS9 - P(9, - 12) * PS7 + PS125 * dt; - nextP(2, 9) = P(0, 9) * PS12 - P(1, 9) * PS13 + P(2, 9) + P(3, 9) * PS11 - P(9, 10) * PS9 - P(9, 11) * PS34 + P(9, - 12) * PS6 + PS150 * dt; - nextP(3, 9) = P(0, 9) * PS13 + P(1, 9) * PS12 - P(2, 9) * PS11 + P(3, 9) + P(9, 10) * PS7 - P(9, 11) * PS6 - P(9, - 12) * PS34 + PS170 * dt; - nextP(4, 9) = P(0, 9) * PS174 + P(1, 9) * PS173 + P(2, 9) * PS175 - P(3, 9) * PS176 + P(4, 9) + P(9, 13) * PS43 + P(9, - 14) * PS172 - P(9, 15) * PS171 + PS200 * dt; - nextP(5, 9) = -P(0, 9) * PS202 - P(1, 9) * PS204 + P(2, 9) * PS201 + P(3, 9) * PS203 + P(5, 9) - P(9, 13) * PS193 + P(9, - 14) * PS75 + P(9, 15) * PS190 + PS218 * dt; - nextP(6, 9) = P(0, 9) * PS216 + P(1, 9) * PS217 - P(2, 9) * PS214 + P(3, 9) * PS215 + P(6, 9) + P(9, 13) * PS199 - P(9, - 14) * PS197 + P(9, 15) * PS87 + PS222 * dt; - nextP(7, 9) = P(4, 9) * dt + P(7, 9) + dt * (P(4, 6) * dt + P(6, 7)); - nextP(8, 9) = P(5, 9) * dt + P(8, 9) + dt * (P(5, 6) * dt + P(6, 8)); - nextP(9, 9) = P(6, 9) * dt + P(9, 9) + dt * (P(6, 6) * dt + P(6, 9)); - nextP(0, 10) = PS14; - nextP(1, 10) = PS105; - nextP(2, 10) = PS133; - nextP(3, 10) = PS151; - nextP(4, 10) = P(0, 10) * PS174 + P(1, 10) * PS173 + P(10, 13) * PS43 + P(10, 14) * PS172 - P(10, 15) * PS171 + P(2, - 10) * PS175 - P(3, 10) * PS176 + P(4, 10); - nextP(5, 10) = -P(0, 10) * PS202 - P(1, 10) * PS204 - P(10, 13) * PS193 + P(10, 14) * PS75 + P(10, 15) * PS190 + P(2, - 10) * PS201 + P(3, 10) * PS203 + P(5, 10); - nextP(6, 10) = P(0, 10) * PS216 + P(1, 10) * PS217 + P(10, 13) * PS199 - P(10, 14) * PS197 + P(10, 15) * PS87 - P(2, - 10) * PS214 + P(3, 10) * PS215 + P(6, 10); - nextP(7, 10) = P(4, 10) * dt + P(7, 10); - nextP(8, 10) = P(5, 10) * dt + P(8, 10); - nextP(9, 10) = P(6, 10) * dt + P(9, 10); - nextP(10, 10) = P(10, 10); - nextP(0, 11) = PS17; - nextP(1, 11) = PS97; - nextP(2, 11) = PS132; - nextP(3, 11) = PS155; - nextP(4, 11) = P(0, 11) * PS174 + P(1, 11) * PS173 + P(11, 13) * PS43 + P(11, 14) * PS172 - P(11, 15) * PS171 + P(2, - 11) * PS175 - P(3, 11) * PS176 + P(4, 11); - nextP(5, 11) = -P(0, 11) * PS202 - P(1, 11) * PS204 - P(11, 13) * PS193 + P(11, 14) * PS75 + P(11, 15) * PS190 + P(2, - 11) * PS201 + P(3, 11) * PS203 + P(5, 11); - nextP(6, 11) = P(0, 11) * PS216 + P(1, 11) * PS217 + P(11, 13) * PS199 - P(11, 14) * PS197 + P(11, 15) * PS87 - P(2, - 11) * PS214 + P(3, 11) * PS215 + P(6, 11); - nextP(7, 11) = P(4, 11) * dt + P(7, 11); - nextP(8, 11) = P(5, 11) * dt + P(8, 11); - nextP(9, 11) = P(6, 11) * dt + P(9, 11); - nextP(10, 11) = P(10, 11); - nextP(11, 11) = P(11, 11); - nextP(0, 12) = PS20; - nextP(1, 12) = PS107; - nextP(2, 12) = PS127; - nextP(3, 12) = PS154; - nextP(4, 12) = P(0, 12) * PS174 + P(1, 12) * PS173 + P(12, 13) * PS43 + P(12, 14) * PS172 - P(12, 15) * PS171 + P(2, - 12) * PS175 - P(3, 12) * PS176 + P(4, 12); - nextP(5, 12) = -P(0, 12) * PS202 - P(1, 12) * PS204 - P(12, 13) * PS193 + P(12, 14) * PS75 + P(12, 15) * PS190 + P(2, - 12) * PS201 + P(3, 12) * PS203 + P(5, 12); - nextP(6, 12) = P(0, 12) * PS216 + P(1, 12) * PS217 + P(12, 13) * PS199 - P(12, 14) * PS197 + P(12, 15) * PS87 - P(2, - 12) * PS214 + P(3, 12) * PS215 + P(6, 12); - nextP(7, 12) = P(4, 12) * dt + P(7, 12); - nextP(8, 12) = P(5, 12) * dt + P(8, 12); - nextP(9, 12) = P(6, 12) * dt + P(9, 12); - nextP(10, 12) = P(10, 12); - nextP(11, 12) = P(11, 12); - nextP(12, 12) = P(12, 12); - nextP(0, 13) = PS44; - nextP(1, 13) = PS113; - nextP(2, 13) = PS138; - nextP(3, 13) = PS158; - nextP(4, 13) = PS177; - nextP(5, 13) = PS206; - nextP(6, 13) = PS221; - nextP(7, 13) = P(4, 13) * dt + P(7, 13); - nextP(8, 13) = P(5, 13) * dt + P(8, 13); - nextP(9, 13) = P(6, 13) * dt + P(9, 13); - nextP(10, 13) = P(10, 13); - nextP(11, 13) = P(11, 13); - nextP(12, 13) = P(12, 13); - nextP(13, 13) = P(13, 13); - nextP(0, 14) = PS57; - nextP(1, 14) = PS117; - nextP(2, 14) = PS142; - nextP(3, 14) = PS162; - nextP(4, 14) = PS180; - nextP(5, 14) = PS205; - nextP(6, 14) = PS220; - nextP(7, 14) = P(4, 14) * dt + P(7, 14); - nextP(8, 14) = P(5, 14) * dt + P(8, 14); - nextP(9, 14) = P(6, 14) * dt + P(9, 14); - nextP(10, 14) = P(10, 14); - nextP(11, 14) = P(11, 14); - nextP(12, 14) = P(12, 14); - nextP(13, 14) = P(13, 14); - nextP(14, 14) = P(14, 14); - nextP(0, 15) = PS46; - nextP(1, 15) = PS114; - nextP(2, 15) = PS139; - nextP(3, 15) = PS159; - nextP(4, 15) = PS178; - nextP(5, 15) = PS209; - nextP(6, 15) = PS219; - nextP(7, 15) = P(4, 15) * dt + P(7, 15); - nextP(8, 15) = P(5, 15) * dt + P(8, 15); - nextP(9, 15) = P(6, 15) * dt + P(9, 15); - nextP(10, 15) = P(10, 15); - nextP(11, 15) = P(11, 15); - nextP(12, 15) = P(12, 15); - nextP(13, 15) = P(13, 15); - nextP(14, 15) = P(14, 15); - nextP(15, 15) = P(15, 15); - nextP(0, 16) = P(0, 16) - P(1, 16) * PS11 + P(10, 16) * PS6 + P(11, 16) * PS7 + P(12, 16) * PS9 - P(2, 16) * PS12 - P(3, - 16) * PS13; - nextP(1, 16) = P(0, 16) * PS11 + P(1, 16) - P(10, 16) * PS34 + P(11, 16) * PS9 - P(12, 16) * PS7 + P(2, - 16) * PS13 - P(3, 16) * PS12; - nextP(2, 16) = P(0, 16) * PS12 - P(1, 16) * PS13 - P(10, 16) * PS9 - P(11, 16) * PS34 + P(12, 16) * PS6 + P(2, - 16) + P(3, 16) * PS11; - nextP(3, 16) = P(0, 16) * PS13 + P(1, 16) * PS12 + P(10, 16) * PS7 - P(11, 16) * PS6 - P(12, 16) * PS34 - P(2, - 16) * PS11 + P(3, 16); - nextP(4, 16) = P(0, 16) * PS174 + P(1, 16) * PS173 + P(13, 16) * PS43 + P(14, 16) * PS172 - P(15, 16) * PS171 + P(2, - 16) * PS175 - P(3, 16) * PS176 + P(4, 16); - nextP(5, 16) = -P(0, 16) * PS202 - P(1, 16) * PS204 - P(13, 16) * PS193 + P(14, 16) * PS75 + P(15, 16) * PS190 + P(2, - 16) * PS201 + P(3, 16) * PS203 + P(5, 16); - nextP(6, 16) = P(0, 16) * PS216 + P(1, 16) * PS217 + P(13, 16) * PS199 - P(14, 16) * PS197 + P(15, 16) * PS87 - P(2, - 16) * PS214 + P(3, 16) * PS215 + P(6, 16); - nextP(7, 16) = P(4, 16) * dt + P(7, 16); - nextP(8, 16) = P(5, 16) * dt + P(8, 16); - nextP(9, 16) = P(6, 16) * dt + P(9, 16); - nextP(10, 16) = P(10, 16); - nextP(11, 16) = P(11, 16); - nextP(12, 16) = P(12, 16); - nextP(13, 16) = P(13, 16); - nextP(14, 16) = P(14, 16); - nextP(15, 16) = P(15, 16); - nextP(16, 16) = P(16, 16); - nextP(0, 17) = P(0, 17) - P(1, 17) * PS11 + P(10, 17) * PS6 + P(11, 17) * PS7 + P(12, 17) * PS9 - P(2, 17) * PS12 - P(3, - 17) * PS13; - nextP(1, 17) = P(0, 17) * PS11 + P(1, 17) - P(10, 17) * PS34 + P(11, 17) * PS9 - P(12, 17) * PS7 + P(2, - 17) * PS13 - P(3, 17) * PS12; - nextP(2, 17) = P(0, 17) * PS12 - P(1, 17) * PS13 - P(10, 17) * PS9 - P(11, 17) * PS34 + P(12, 17) * PS6 + P(2, - 17) + P(3, 17) * PS11; - nextP(3, 17) = P(0, 17) * PS13 + P(1, 17) * PS12 + P(10, 17) * PS7 - P(11, 17) * PS6 - P(12, 17) * PS34 - P(2, - 17) * PS11 + P(3, 17); - nextP(4, 17) = P(0, 17) * PS174 + P(1, 17) * PS173 + P(13, 17) * PS43 + P(14, 17) * PS172 - P(15, 17) * PS171 + P(2, - 17) * PS175 - P(3, 17) * PS176 + P(4, 17); - nextP(5, 17) = -P(0, 17) * PS202 - P(1, 17) * PS204 - P(13, 17) * PS193 + P(14, 17) * PS75 + P(15, 17) * PS190 + P(2, - 17) * PS201 + P(3, 17) * PS203 + P(5, 17); - nextP(6, 17) = P(0, 17) * PS216 + P(1, 17) * PS217 + P(13, 17) * PS199 - P(14, 17) * PS197 + P(15, 17) * PS87 - P(2, - 17) * PS214 + P(3, 17) * PS215 + P(6, 17); - nextP(7, 17) = P(4, 17) * dt + P(7, 17); - nextP(8, 17) = P(5, 17) * dt + P(8, 17); - nextP(9, 17) = P(6, 17) * dt + P(9, 17); - nextP(10, 17) = P(10, 17); - nextP(11, 17) = P(11, 17); - nextP(12, 17) = P(12, 17); - nextP(13, 17) = P(13, 17); - nextP(14, 17) = P(14, 17); - nextP(15, 17) = P(15, 17); - nextP(16, 17) = P(16, 17); - nextP(17, 17) = P(17, 17); - nextP(0, 18) = P(0, 18) - P(1, 18) * PS11 + P(10, 18) * PS6 + P(11, 18) * PS7 + P(12, 18) * PS9 - P(2, 18) * PS12 - P(3, - 18) * PS13; - nextP(1, 18) = P(0, 18) * PS11 + P(1, 18) - P(10, 18) * PS34 + P(11, 18) * PS9 - P(12, 18) * PS7 + P(2, - 18) * PS13 - P(3, 18) * PS12; - nextP(2, 18) = P(0, 18) * PS12 - P(1, 18) * PS13 - P(10, 18) * PS9 - P(11, 18) * PS34 + P(12, 18) * PS6 + P(2, - 18) + P(3, 18) * PS11; - nextP(3, 18) = P(0, 18) * PS13 + P(1, 18) * PS12 + P(10, 18) * PS7 - P(11, 18) * PS6 - P(12, 18) * PS34 - P(2, - 18) * PS11 + P(3, 18); - nextP(4, 18) = P(0, 18) * PS174 + P(1, 18) * PS173 + P(13, 18) * PS43 + P(14, 18) * PS172 - P(15, 18) * PS171 + P(2, - 18) * PS175 - P(3, 18) * PS176 + P(4, 18); - nextP(5, 18) = -P(0, 18) * PS202 - P(1, 18) * PS204 - P(13, 18) * PS193 + P(14, 18) * PS75 + P(15, 18) * PS190 + P(2, - 18) * PS201 + P(3, 18) * PS203 + P(5, 18); - nextP(6, 18) = P(0, 18) * PS216 + P(1, 18) * PS217 + P(13, 18) * PS199 - P(14, 18) * PS197 + P(15, 18) * PS87 - P(2, - 18) * PS214 + P(3, 18) * PS215 + P(6, 18); - nextP(7, 18) = P(4, 18) * dt + P(7, 18); - nextP(8, 18) = P(5, 18) * dt + P(8, 18); - nextP(9, 18) = P(6, 18) * dt + P(9, 18); - nextP(10, 18) = P(10, 18); - nextP(11, 18) = P(11, 18); - nextP(12, 18) = P(12, 18); - nextP(13, 18) = P(13, 18); - nextP(14, 18) = P(14, 18); - nextP(15, 18) = P(15, 18); - nextP(16, 18) = P(16, 18); - nextP(17, 18) = P(17, 18); - nextP(18, 18) = P(18, 18); - nextP(0, 19) = P(0, 19) - P(1, 19) * PS11 + P(10, 19) * PS6 + P(11, 19) * PS7 + P(12, 19) * PS9 - P(2, 19) * PS12 - P(3, - 19) * PS13; - nextP(1, 19) = P(0, 19) * PS11 + P(1, 19) - P(10, 19) * PS34 + P(11, 19) * PS9 - P(12, 19) * PS7 + P(2, - 19) * PS13 - P(3, 19) * PS12; - nextP(2, 19) = P(0, 19) * PS12 - P(1, 19) * PS13 - P(10, 19) * PS9 - P(11, 19) * PS34 + P(12, 19) * PS6 + P(2, - 19) + P(3, 19) * PS11; - nextP(3, 19) = P(0, 19) * PS13 + P(1, 19) * PS12 + P(10, 19) * PS7 - P(11, 19) * PS6 - P(12, 19) * PS34 - P(2, - 19) * PS11 + P(3, 19); - nextP(4, 19) = P(0, 19) * PS174 + P(1, 19) * PS173 + P(13, 19) * PS43 + P(14, 19) * PS172 - P(15, 19) * PS171 + P(2, - 19) * PS175 - P(3, 19) * PS176 + P(4, 19); - nextP(5, 19) = -P(0, 19) * PS202 - P(1, 19) * PS204 - P(13, 19) * PS193 + P(14, 19) * PS75 + P(15, 19) * PS190 + P(2, - 19) * PS201 + P(3, 19) * PS203 + P(5, 19); - nextP(6, 19) = P(0, 19) * PS216 + P(1, 19) * PS217 + P(13, 19) * PS199 - P(14, 19) * PS197 + P(15, 19) * PS87 - P(2, - 19) * PS214 + P(3, 19) * PS215 + P(6, 19); - nextP(7, 19) = P(4, 19) * dt + P(7, 19); - nextP(8, 19) = P(5, 19) * dt + P(8, 19); - nextP(9, 19) = P(6, 19) * dt + P(9, 19); - nextP(10, 19) = P(10, 19); - nextP(11, 19) = P(11, 19); - nextP(12, 19) = P(12, 19); - nextP(13, 19) = P(13, 19); - nextP(14, 19) = P(14, 19); - nextP(15, 19) = P(15, 19); - nextP(16, 19) = P(16, 19); - nextP(17, 19) = P(17, 19); - nextP(18, 19) = P(18, 19); - nextP(19, 19) = P(19, 19); - nextP(0, 20) = P(0, 20) - P(1, 20) * PS11 + P(10, 20) * PS6 + P(11, 20) * PS7 + P(12, 20) * PS9 - P(2, 20) * PS12 - P(3, - 20) * PS13; - nextP(1, 20) = P(0, 20) * PS11 + P(1, 20) - P(10, 20) * PS34 + P(11, 20) * PS9 - P(12, 20) * PS7 + P(2, - 20) * PS13 - P(3, 20) * PS12; - nextP(2, 20) = P(0, 20) * PS12 - P(1, 20) * PS13 - P(10, 20) * PS9 - P(11, 20) * PS34 + P(12, 20) * PS6 + P(2, - 20) + P(3, 20) * PS11; - nextP(3, 20) = P(0, 20) * PS13 + P(1, 20) * PS12 + P(10, 20) * PS7 - P(11, 20) * PS6 - P(12, 20) * PS34 - P(2, - 20) * PS11 + P(3, 20); - nextP(4, 20) = P(0, 20) * PS174 + P(1, 20) * PS173 + P(13, 20) * PS43 + P(14, 20) * PS172 - P(15, 20) * PS171 + P(2, - 20) * PS175 - P(3, 20) * PS176 + P(4, 20); - nextP(5, 20) = -P(0, 20) * PS202 - P(1, 20) * PS204 - P(13, 20) * PS193 + P(14, 20) * PS75 + P(15, 20) * PS190 + P(2, - 20) * PS201 + P(3, 20) * PS203 + P(5, 20); - nextP(6, 20) = P(0, 20) * PS216 + P(1, 20) * PS217 + P(13, 20) * PS199 - P(14, 20) * PS197 + P(15, 20) * PS87 - P(2, - 20) * PS214 + P(3, 20) * PS215 + P(6, 20); - nextP(7, 20) = P(4, 20) * dt + P(7, 20); - nextP(8, 20) = P(5, 20) * dt + P(8, 20); - nextP(9, 20) = P(6, 20) * dt + P(9, 20); - nextP(10, 20) = P(10, 20); - nextP(11, 20) = P(11, 20); - nextP(12, 20) = P(12, 20); - nextP(13, 20) = P(13, 20); - nextP(14, 20) = P(14, 20); - nextP(15, 20) = P(15, 20); - nextP(16, 20) = P(16, 20); - nextP(17, 20) = P(17, 20); - nextP(18, 20) = P(18, 20); - nextP(19, 20) = P(19, 20); - nextP(20, 20) = P(20, 20); - nextP(0, 21) = P(0, 21) - P(1, 21) * PS11 + P(10, 21) * PS6 + P(11, 21) * PS7 + P(12, 21) * PS9 - P(2, 21) * PS12 - P(3, - 21) * PS13; - nextP(1, 21) = P(0, 21) * PS11 + P(1, 21) - P(10, 21) * PS34 + P(11, 21) * PS9 - P(12, 21) * PS7 + P(2, - 21) * PS13 - P(3, 21) * PS12; - nextP(2, 21) = P(0, 21) * PS12 - P(1, 21) * PS13 - P(10, 21) * PS9 - P(11, 21) * PS34 + P(12, 21) * PS6 + P(2, - 21) + P(3, 21) * PS11; - nextP(3, 21) = P(0, 21) * PS13 + P(1, 21) * PS12 + P(10, 21) * PS7 - P(11, 21) * PS6 - P(12, 21) * PS34 - P(2, - 21) * PS11 + P(3, 21); - nextP(4, 21) = P(0, 21) * PS174 + P(1, 21) * PS173 + P(13, 21) * PS43 + P(14, 21) * PS172 - P(15, 21) * PS171 + P(2, - 21) * PS175 - P(3, 21) * PS176 + P(4, 21); - nextP(5, 21) = -P(0, 21) * PS202 - P(1, 21) * PS204 - P(13, 21) * PS193 + P(14, 21) * PS75 + P(15, 21) * PS190 + P(2, - 21) * PS201 + P(3, 21) * PS203 + P(5, 21); - nextP(6, 21) = P(0, 21) * PS216 + P(1, 21) * PS217 + P(13, 21) * PS199 - P(14, 21) * PS197 + P(15, 21) * PS87 - P(2, - 21) * PS214 + P(3, 21) * PS215 + P(6, 21); - nextP(7, 21) = P(4, 21) * dt + P(7, 21); - nextP(8, 21) = P(5, 21) * dt + P(8, 21); - nextP(9, 21) = P(6, 21) * dt + P(9, 21); - nextP(10, 21) = P(10, 21); - nextP(11, 21) = P(11, 21); - nextP(12, 21) = P(12, 21); - nextP(13, 21) = P(13, 21); - nextP(14, 21) = P(14, 21); - nextP(15, 21) = P(15, 21); - nextP(16, 21) = P(16, 21); - nextP(17, 21) = P(17, 21); - nextP(18, 21) = P(18, 21); - nextP(19, 21) = P(19, 21); - nextP(20, 21) = P(20, 21); - nextP(21, 21) = P(21, 21); - nextP(0, 22) = P(0, 22) - P(1, 22) * PS11 + P(10, 22) * PS6 + P(11, 22) * PS7 + P(12, 22) * PS9 - P(2, 22) * PS12 - P(3, - 22) * PS13; - nextP(1, 22) = P(0, 22) * PS11 + P(1, 22) - P(10, 22) * PS34 + P(11, 22) * PS9 - P(12, 22) * PS7 + P(2, - 22) * PS13 - P(3, 22) * PS12; - nextP(2, 22) = P(0, 22) * PS12 - P(1, 22) * PS13 - P(10, 22) * PS9 - P(11, 22) * PS34 + P(12, 22) * PS6 + P(2, - 22) + P(3, 22) * PS11; - nextP(3, 22) = P(0, 22) * PS13 + P(1, 22) * PS12 + P(10, 22) * PS7 - P(11, 22) * PS6 - P(12, 22) * PS34 - P(2, - 22) * PS11 + P(3, 22); - nextP(4, 22) = P(0, 22) * PS174 + P(1, 22) * PS173 + P(13, 22) * PS43 + P(14, 22) * PS172 - P(15, 22) * PS171 + P(2, - 22) * PS175 - P(3, 22) * PS176 + P(4, 22); - nextP(5, 22) = -P(0, 22) * PS202 - P(1, 22) * PS204 - P(13, 22) * PS193 + P(14, 22) * PS75 + P(15, 22) * PS190 + P(2, - 22) * PS201 + P(3, 22) * PS203 + P(5, 22); - nextP(6, 22) = P(0, 22) * PS216 + P(1, 22) * PS217 + P(13, 22) * PS199 - P(14, 22) * PS197 + P(15, 22) * PS87 - P(2, - 22) * PS214 + P(3, 22) * PS215 + P(6, 22); - nextP(7, 22) = P(4, 22) * dt + P(7, 22); - nextP(8, 22) = P(5, 22) * dt + P(8, 22); - nextP(9, 22) = P(6, 22) * dt + P(9, 22); - nextP(10, 22) = P(10, 22); - nextP(11, 22) = P(11, 22); - nextP(12, 22) = P(12, 22); - nextP(13, 22) = P(13, 22); - nextP(14, 22) = P(14, 22); - nextP(15, 22) = P(15, 22); - nextP(16, 22) = P(16, 22); - nextP(17, 22) = P(17, 22); - nextP(18, 22) = P(18, 22); - nextP(19, 22) = P(19, 22); - nextP(20, 22) = P(20, 22); - nextP(21, 22) = P(21, 22); - nextP(22, 22) = P(22, 22); - nextP(0, 23) = P(0, 23) - P(1, 23) * PS11 + P(10, 23) * PS6 + P(11, 23) * PS7 + P(12, 23) * PS9 - P(2, 23) * PS12 - P(3, - 23) * PS13; - nextP(1, 23) = P(0, 23) * PS11 + P(1, 23) - P(10, 23) * PS34 + P(11, 23) * PS9 - P(12, 23) * PS7 + P(2, - 23) * PS13 - P(3, 23) * PS12; - nextP(2, 23) = P(0, 23) * PS12 - P(1, 23) * PS13 - P(10, 23) * PS9 - P(11, 23) * PS34 + P(12, 23) * PS6 + P(2, - 23) + P(3, 23) * PS11; - nextP(3, 23) = P(0, 23) * PS13 + P(1, 23) * PS12 + P(10, 23) * PS7 - P(11, 23) * PS6 - P(12, 23) * PS34 - P(2, - 23) * PS11 + P(3, 23); - nextP(4, 23) = P(0, 23) * PS174 + P(1, 23) * PS173 + P(13, 23) * PS43 + P(14, 23) * PS172 - P(15, 23) * PS171 + P(2, - 23) * PS175 - P(3, 23) * PS176 + P(4, 23); - nextP(5, 23) = -P(0, 23) * PS202 - P(1, 23) * PS204 - P(13, 23) * PS193 + P(14, 23) * PS75 + P(15, 23) * PS190 + P(2, - 23) * PS201 + P(3, 23) * PS203 + P(5, 23); - nextP(6, 23) = P(0, 23) * PS216 + P(1, 23) * PS217 + P(13, 23) * PS199 - P(14, 23) * PS197 + P(15, 23) * PS87 - P(2, - 23) * PS214 + P(3, 23) * PS215 + P(6, 23); - nextP(7, 23) = P(4, 23) * dt + P(7, 23); - nextP(8, 23) = P(5, 23) * dt + P(8, 23); - nextP(9, 23) = P(6, 23) * dt + P(9, 23); - nextP(10, 23) = P(10, 23); - nextP(11, 23) = P(11, 23); - nextP(12, 23) = P(12, 23); - nextP(13, 23) = P(13, 23); - nextP(14, 23) = P(14, 23); - nextP(15, 23) = P(15, 23); - nextP(16, 23) = P(16, 23); - nextP(17, 23) = P(17, 23); - nextP(18, 23) = P(18, 23); - nextP(19, 23) = P(19, 23); - nextP(20, 23) = P(20, 23); - nextP(21, 23) = P(21, 23); - nextP(22, 23) = P(22, 23); - nextP(23, 23) = P(23, 23); - - // save output - for (int col = 0; col <= 23; col++) { - for (int row = 0; row <= col; row++) { - nextP_sympy(row, col) = nextP(row, col); - } - } - } - - { - Vector24f state_vector{}; - state_vector(0) = q0; - state_vector(1) = q1; - state_vector(2) = q2; - state_vector(3) = q3; - state_vector(10) = dax_b; - state_vector(11) = day_b; - state_vector(12) = daz_b; - state_vector(13) = dvx_b; - state_vector(14) = dvy_b; - state_vector(15) = dvz_b; - - const Vector3f d_vel(dvx, dvy, dvz); - const Vector3f d_ang(dax, day, daz); - - EXPECT_FLOAT_EQ(daxVar, dayVar); - EXPECT_FLOAT_EQ(daxVar, dazVar); - - const float d_ang_var = daxVar; // derivation assumes same variance on all gyro axes - const Vector3f d_vel_var(dvxVar, dvyVar, dvzVar); - - sym::PredictCovariance(state_vector, P, d_vel, d_vel_var, d_ang, d_ang_var, dt, &nextP_symforce); - } - - DiffRatioReport report = computeDiffRatioSquareMatrix24f(nextP_sympy, nextP_symforce); - EXPECT_LT(report.max_diff_fraction, 2e-5f) << "Max diff fraction = " << report.max_diff_fraction << - " location index = " << report.max_row << " sympy = " << report.max_v1 << " symforce = " << report.max_v2; -} diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index 71b09cc3e7..3c5f06e306 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -120,13 +120,13 @@ public: void learningCorrectAccelBias() { const Dcmf R_to_earth = Dcmf(_ekf->getQuaternion()); - const Vector3f dvel_bias_var = _ekf_wrapper.getDeltaVelBiasVariance(); + const Vector3f accel_bias_var = _ekf->getAccelBiasVariance(); const Vector3f accel_bias = _ekf->getAccelBias(); for (int i = 0; i < 3; i++) { if (fabsf(R_to_earth(2, i)) > 0.8f) { // Highly observable, the variance decreases - EXPECT_LT(dvel_bias_var(i), 4.0e-6f) << "axis " << i; + EXPECT_LT(accel_bias_var(i), 4.0e-2f) << "axis " << i; } EXPECT_LT(accel_bias(i), 4.0e-6f) << "axis " << i; diff --git a/src/modules/ekf2/test/test_EKF_utils.cpp b/src/modules/ekf2/test/test_EKF_utils.cpp index 77a99a35d4..144d6e6e94 100644 --- a/src/modules/ekf2/test/test_EKF_utils.cpp +++ b/src/modules/ekf2/test/test_EKF_utils.cpp @@ -42,8 +42,6 @@ #include #include -#include "EKF/utils.hpp" - TEST(eclPowfTest, compareToStandardImplementation) { std::vector exponents = {-3, -2, -1, -0, 0, 1, 2, 3}; @@ -51,7 +49,7 @@ TEST(eclPowfTest, compareToStandardImplementation) for (auto const exponent : exponents) { for (auto const basis : bases) { - EXPECT_EQ(ecl::powf(basis, exponent), + EXPECT_EQ(powf(basis, exponent), std::pow(basis, static_cast(exponent))); } } diff --git a/src/modules/ekf2/test/test_EKF_yaw_estimator_generated.cpp b/src/modules/ekf2/test/test_EKF_yaw_estimator_generated.cpp index 98537b1cba..a152275ca3 100644 --- a/src/modules/ekf2/test/test_EKF_yaw_estimator_generated.cpp +++ b/src/modules/ekf2/test/test_EKF_yaw_estimator_generated.cpp @@ -74,9 +74,9 @@ void sympyYawEstUpdate(const SquareMatrix3f &P, float velObsVar, SquareMatrix