From b418980491891a19c6b71ee5aa80876953c07807 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sat, 5 Aug 2023 20:46:27 -0400 Subject: [PATCH] [WIP] ekf2: innovation sequence monitoring and estimator aid src status consistency --- .vscode/settings.json | 3 +- msg/EstimatorAidSource1d.msg | 9 +- msg/EstimatorAidSource2d.msg | 9 +- msg/EstimatorAidSource3d.msg | 3 + src/modules/ekf2/EKF/airspeed_fusion.cpp | 47 +- src/modules/ekf2/EKF/aux_global_position.cpp | 18 +- src/modules/ekf2/EKF/auxvel_fusion.cpp | 9 +- src/modules/ekf2/EKF/baro_height_control.cpp | 14 +- src/modules/ekf2/EKF/drag_fusion.cpp | 46 +- src/modules/ekf2/EKF/ekf.cpp | 48 -- src/modules/ekf2/EKF/ekf.h | 243 ++++--- src/modules/ekf2/EKF/ev_control.cpp | 3 - src/modules/ekf2/EKF/ev_height_control.cpp | 16 +- src/modules/ekf2/EKF/ev_pos_control.cpp | 18 +- src/modules/ekf2/EKF/ev_vel_control.cpp | 22 +- src/modules/ekf2/EKF/ev_yaw_control.cpp | 31 +- src/modules/ekf2/EKF/fake_height_control.cpp | 5 +- src/modules/ekf2/EKF/fake_pos_control.cpp | 13 +- src/modules/ekf2/EKF/gnss_height_control.cpp | 13 +- src/modules/ekf2/EKF/gps_control.cpp | 27 +- src/modules/ekf2/EKF/gps_yaw_fusion.cpp | 21 +- src/modules/ekf2/EKF/gravity_fusion.cpp | 22 +- src/modules/ekf2/EKF/mag_3d_control.cpp | 35 +- src/modules/ekf2/EKF/mag_fusion.cpp | 77 +-- src/modules/ekf2/EKF/mag_heading_control.cpp | 35 +- src/modules/ekf2/EKF/optflow_fusion.cpp | 40 +- src/modules/ekf2/EKF/optical_flow_control.cpp | 2 - src/modules/ekf2/EKF/range_height_control.cpp | 34 +- src/modules/ekf2/EKF/sideslip_fusion.cpp | 28 +- src/modules/ekf2/EKF/terrain_estimator.cpp | 52 +- src/modules/ekf2/EKF/vel_pos_fusion.cpp | 186 +++--- src/modules/ekf2/EKF/yaw_fusion.cpp | 31 +- .../test/change_indication/ekf_gsf_reset.csv | 610 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 338 +++++----- 34 files changed, 1058 insertions(+), 1050 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 67016f0983..57988c26a3 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -128,5 +128,6 @@ "yaml.schemas": { "${workspaceFolder}/validation/module_schema.yaml": "${workspaceFolder}/src/modules/*/module.yaml" }, - "ros.distro": "humble" + "ros.distro": "humble", + "cmake.options.statusBarVisibility": "visible" } diff --git a/msg/EstimatorAidSource1d.msg b/msg/EstimatorAidSource1d.msg index 78273d6b06..7cac899678 100644 --- a/msg/EstimatorAidSource1d.msg +++ b/msg/EstimatorAidSource1d.msg @@ -10,9 +10,12 @@ uint64 time_last_fuse float32 observation float32 observation_variance -float32 innovation -float32 innovation_variance -float32 test_ratio +float32 innovation # +float32 innovation_filtered +float32 innovation_variance # + +float32 test_ratio # normalized innovation squared +float32 test_ratio_filtered # signed test ratio filtered bool innovation_rejected # true if the observation has been rejected bool fused # true if the sample was successfully fused diff --git a/msg/EstimatorAidSource2d.msg b/msg/EstimatorAidSource2d.msg index 98e645a3ec..ec6a3e5581 100644 --- a/msg/EstimatorAidSource2d.msg +++ b/msg/EstimatorAidSource2d.msg @@ -10,9 +10,12 @@ uint64 time_last_fuse float32[2] observation float32[2] observation_variance -float32[2] innovation -float32[2] innovation_variance -float32[2] test_ratio +float32[2] innovation # +float32[2] innovation_filtered +float32[2] innovation_variance # + +float32[2] test_ratio # normalized innovation squared +float32[2] test_ratio_filtered # signed test ratio filtered bool innovation_rejected # true if the observation has been rejected bool fused # true if the sample was successfully fused diff --git a/msg/EstimatorAidSource3d.msg b/msg/EstimatorAidSource3d.msg index deb4c05bd0..edf6669504 100644 --- a/msg/EstimatorAidSource3d.msg +++ b/msg/EstimatorAidSource3d.msg @@ -11,8 +11,11 @@ float32[3] observation float32[3] observation_variance float32[3] innovation +float32[3] innovation_filtered float32[3] innovation_variance + float32[3] test_ratio +float32[3] test_ratio_filtered bool innovation_rejected # true if the observation has been rejected bool fused # true if the sample was successfully fused diff --git a/src/modules/ekf2/EKF/airspeed_fusion.cpp b/src/modules/ekf2/EKF/airspeed_fusion.cpp index fde836232b..b73b5777b6 100644 --- a/src/modules/ekf2/EKF/airspeed_fusion.cpp +++ b/src/modules/ekf2/EKF/airspeed_fusion.cpp @@ -63,6 +63,7 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) } #if defined(CONFIG_EKF2_GNSS) + // clear yaw estimator airspeed (updated later with true airspeed if airspeed fusion is active) if (_control_status.flags.fixed_wing) { if (_control_status.flags.in_air && !_control_status.flags.vehicle_at_rest) { @@ -74,6 +75,7 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) _yawEstimator.setTrueAirspeed(0.f); } } + #endif // CONFIG_EKF2_GNSS if (_params.arsp_thr <= 0.f) { @@ -87,13 +89,19 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) updateAirspeed(airspeed_sample, _aid_src_airspeed); - _innov_check_fail_status.flags.reject_airspeed = _aid_src_airspeed.innovation_rejected; // TODO: remove this redundant flag + // TODO: remove this redundant flag + _innov_check_fail_status.flags.reject_airspeed = _aid_src_airspeed.innovation_rejected; + + const bool continuing_conditions_passing = _control_status.flags.in_air + && _control_status.flags.fixed_wing + && !_control_status.flags.fake_pos; - const bool continuing_conditions_passing = _control_status.flags.in_air && _control_status.flags.fixed_wing && !_control_status.flags.fake_pos; const bool is_airspeed_significant = airspeed_sample.true_airspeed > _params.arsp_thr; const bool is_airspeed_consistent = (_aid_src_airspeed.test_ratio > 0.f && _aid_src_airspeed.test_ratio < 1.f); - const bool starting_conditions_passing = continuing_conditions_passing && is_airspeed_significant - && (is_airspeed_consistent || !_control_status.flags.wind); // if wind isn't already estimated, the states are reset when starting airspeed fusion + + const bool starting_conditions_passing = continuing_conditions_passing + && is_airspeed_significant + && (is_airspeed_consistent || !_control_status.flags.wind); // if wind isn't already estimated, the states are reset when starting airspeed fusion if (_control_status.flags.fuse_aspd) { if (continuing_conditions_passing) { @@ -140,26 +148,22 @@ void Ekf::controlAirDataFusion(const imuSample &imu_delayed) void Ekf::updateAirspeed(const airspeedSample &airspeed_sample, estimator_aid_source1d_s &aid_src) const { - // reset flags - resetEstimatorAidStatus(aid_src); - // Variance for true airspeed measurement - (m/sec)^2 const float R = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) * math::constrain(airspeed_sample.eas2tas, 0.9f, 10.0f)); float innov = 0.f; float innov_var = 0.f; - sym::ComputeAirspeedInnovAndInnovVar(_state.vector(), P, airspeed_sample.true_airspeed, R, FLT_EPSILON, &innov, &innov_var); + sym::ComputeAirspeedInnovAndInnovVar(_state.vector(), P, airspeed_sample.true_airspeed, R, FLT_EPSILON, + &innov, &innov_var); - aid_src.observation = airspeed_sample.true_airspeed; - aid_src.observation_variance = R; - aid_src.innovation = innov; - aid_src.innovation_variance = innov_var; - - aid_src.timestamp_sample = airspeed_sample.time_us; - - const float innov_gate = fmaxf(_params.tas_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(aid_src, innov_gate); + updateEstimatorAidStatus(aid_src, + airspeed_sample.time_us, // sample timestamp + airspeed_sample.true_airspeed, // observation + R, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.tas_innov_gate, 1.f)); // gate sigma } void Ekf::fuseAirspeed(const airspeedSample &airspeed_sample, estimator_aid_source1d_s &aid_src) @@ -222,7 +226,6 @@ void Ekf::stopAirspeedFusion() { if (_control_status.flags.fuse_aspd) { ECL_INFO("stopping airspeed fusion"); - resetEstimatorAidStatus(_aid_src_airspeed); _control_status.flags.fuse_aspd = false; #if defined(CONFIG_EKF2_GNSS) @@ -236,14 +239,16 @@ void Ekf::resetWindUsingAirspeed(const airspeedSample &airspeed_sample) constexpr float sideslip_var = sq(math::radians(15.0f)); const float euler_yaw = getEulerYaw(_R_to_earth); - const float airspeed_var = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) * math::constrain(airspeed_sample.eas2tas, 0.9f, 10.0f)); + const float airspeed_var = sq(math::constrain(_params.eas_noise, 0.5f, 5.0f) + * math::constrain(airspeed_sample.eas2tas, 0.9f, 10.0f)); matrix::SquareMatrix P_wind; - sym::ComputeWindInitAndCovFromAirspeed(_state.vel, euler_yaw, airspeed_sample.true_airspeed, getVelocityVariance(), getYawVar(), sideslip_var, airspeed_var, &_state.wind_vel, &P_wind); + sym::ComputeWindInitAndCovFromAirspeed(_state.vel, euler_yaw, airspeed_sample.true_airspeed, getVelocityVariance(), + getYawVar(), sideslip_var, airspeed_var, &_state.wind_vel, &P_wind); resetStateCovariance(P_wind); ECL_INFO("reset wind using airspeed to (%.3f, %.3f)", (double)_state.wind_vel(0), (double)_state.wind_vel(1)); - _aid_src_airspeed.time_last_fuse = _time_delayed_us; + updateEstimatorAidStatusStateReset(_aid_src_airspeed, airspeed_sample.time_us, airspeed_sample.true_airspeed, airspeed_var); } diff --git a/src/modules/ekf2/EKF/aux_global_position.cpp b/src/modules/ekf2/EKF/aux_global_position.cpp index 539643513c..5f8974388a 100644 --- a/src/modules/ekf2/EKF/aux_global_position.cpp +++ b/src/modules/ekf2/EKF/aux_global_position.cpp @@ -80,22 +80,23 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed //const float hgt = ekf.getEkfGlobalOriginAltitude() - (float)sample.altitude; // relax the upper observation noise limit which prevents bad measurements perturbing the position estimate float pos_noise = math::max(sample.eph, _param_ekf2_agp_noise.get()); - const float pos_var = sq(pos_noise); + const float pos_var = math::max(sq(pos_noise), sq(0.01f)); const Vector2f pos_obs_var(pos_var, pos_var); - ekf.updateHorizontalPositionAidSrcStatus(sample.time_us, - position, // observation - pos_obs_var, // observation variance - math::max(_param_ekf2_agp_gate.get(), 1.f), // innovation gate - aid_src); + ekf.updateHorizontalPositionAidStatus(aid_src, + sample.time_us, + position, // observation + pos_obs_var, // observation variance + math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate } const bool starting_conditions = PX4_ISFINITE(sample.latitude) && PX4_ISFINITE(sample.longitude) - && ekf.control_status_flags().yaw_align; + && ekf.control_status_flags().yaw_align; const bool continuing_conditions = starting_conditions && ekf.global_origin_valid(); switch (_state) { case State::stopped: + /* FALLTHROUGH */ case State::starting: if (starting_conditions) { @@ -113,6 +114,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed } } } + break; case State::active: @@ -123,6 +125,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed ekf.disableControlStatusAuxGpos(); _state = State::stopped; } + break; default: @@ -133,6 +136,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed aid_src.timestamp = hrt_absolute_time(); _estimator_aid_src_aux_global_position_pub.publish(aid_src); #endif // MODULE_NAME + } else if ((_state != State::stopped) && isTimedOut(_time_last_buffer_push, imu_delayed.time_us, (uint64_t)5e6)) { ekf.disableControlStatusAuxGpos(); _state = State::stopped; diff --git a/src/modules/ekf2/EKF/auxvel_fusion.cpp b/src/modules/ekf2/EKF/auxvel_fusion.cpp index dbe88ccb87..173c7fd83c 100644 --- a/src/modules/ekf2/EKF/auxvel_fusion.cpp +++ b/src/modules/ekf2/EKF/auxvel_fusion.cpp @@ -40,9 +40,11 @@ void Ekf::controlAuxVelFusion() if (_auxvel_buffer->pop_first_older_than(_time_delayed_us, &auxvel_sample_delayed)) { - resetEstimatorAidStatus(_aid_src_aux_vel); - - updateVelocityAidSrcStatus(auxvel_sample_delayed.time_us, auxvel_sample_delayed.vel, auxvel_sample_delayed.velVar, fmaxf(_params.auxvel_gate, 1.f), _aid_src_aux_vel); + updateVelocityAidStatus(_aid_src_aux_vel, + auxvel_sample_delayed.time_us, // sample timestamp + auxvel_sample_delayed.vel, // observation + auxvel_sample_delayed.velVar, // observation variance + math::max(_params.auxvel_gate, 1.f)); // gate sigma if (isHorizontalAidingActive()) { fuseVelocity(_aid_src_aux_vel); @@ -55,5 +57,4 @@ void Ekf::stopAuxVelFusion() { ECL_INFO("stopping aux vel fusion"); //_control_status.flags.aux_vel = false; - resetEstimatorAidStatus(_aid_src_aux_vel); } diff --git a/src/modules/ekf2/EKF/baro_height_control.cpp b/src/modules/ekf2/EKF/baro_height_control.cpp index def9a885f3..862c14aac5 100644 --- a/src/modules/ekf2/EKF/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/baro_height_control.cpp @@ -59,8 +59,6 @@ void Ekf::controlBaroHeightFusion() const float measurement_var = sq(_params.baro_noise); - const float innov_gate = fmaxf(_params.baro_innov_gate, 1.f); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); if (measurement_valid) { @@ -80,11 +78,11 @@ void Ekf::controlBaroHeightFusion() } // vertical position innovation - baro measurement has opposite sign to earth z axis - updateVerticalPositionAidSrcStatus(baro_sample.time_us, - -(measurement - bias_est.getBias()), - measurement_var + bias_est.getBiasVar(), - innov_gate, - aid_src); + updateVerticalPositionAidStatus(aid_src, + baro_sample.time_us, + -(measurement - bias_est.getBias()), // observation + measurement_var + bias_est.getBiasVar(), // observation variance + math::max(_params.baro_innov_gate, 1.f)); // gate sigma // Compensate for positive static pressure transients (negative vertical position innovations) // caused by rotor wash ground interaction by applying a temporary deadzone to baro innovations. @@ -121,7 +119,6 @@ void Ekf::controlBaroHeightFusion() && isNewestSampleRecent(_time_last_baro_buffer_push, 2 * BARO_MAX_INTERVAL); if (_control_status.flags.baro_hgt) { - if (continuing_conditions_passing) { fuseVerticalPosition(aid_src); @@ -191,7 +188,6 @@ void Ekf::stopBaroHgtFusion() } _baro_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_baro_hgt); _control_status.flags.baro_hgt = false; } diff --git a/src/modules/ekf2/EKF/drag_fusion.cpp b/src/modules/ekf2/EKF/drag_fusion.cpp index 287bfb69f9..b4ff1ce525 100644 --- a/src/modules/ekf2/EKF/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/drag_fusion.cpp @@ -105,12 +105,15 @@ void Ekf::fuseDrag(const dragSample &drag_sample) bcoef_inv(1) = bcoef_inv(0); } - _aid_src_drag.timestamp_sample = drag_sample.time_us; - _aid_src_drag.fused = false; - bool fused[] {false, false}; - VectorState Kfusion; + Vector2f observation{}; + Vector2f observation_variance{R_ACC, R_ACC}; + Vector2f innovation{}; + Vector2f innovation_variance{NAN, NAN}; + + // Apply an innovation consistency check with a 5 Sigma threshold + const float innov_gate = 5.f; // perform sequential fusion of XY specific forces for (uint8_t axis_index = 0; axis_index < 2; axis_index++) { @@ -122,14 +125,14 @@ void Ekf::fuseDrag(const dragSample &drag_sample) // parallel to the rotor disc and mass flow through the rotor disc. const float pred_acc = -0.5f * bcoef_inv(axis_index) * rho * rel_wind_body(axis_index) * rel_wind_speed - rel_wind_body(axis_index) * mcoef_corrrected; - _aid_src_drag.observation[axis_index] = mea_acc; - _aid_src_drag.observation_variance[axis_index] = R_ACC; - _aid_src_drag.innovation[axis_index] = pred_acc - mea_acc; - _aid_src_drag.innovation_variance[axis_index] = NAN; // reset + observation(axis_index) = mea_acc; + innovation(axis_index) = pred_acc - mea_acc; + + VectorState Kfusion; if (axis_index == 0) { sym::ComputeDragXInnovVarAndK(state_vector_prev, P, rho, bcoef_inv(axis_index), mcoef_corrrected, R_ACC, FLT_EPSILON, - &_aid_src_drag.innovation_variance[axis_index], &Kfusion); + &innovation_variance(axis_index), &Kfusion); if (!using_bcoef_x && !using_mcoef) { continue; @@ -137,32 +140,39 @@ void Ekf::fuseDrag(const dragSample &drag_sample) } else if (axis_index == 1) { sym::ComputeDragYInnovVarAndK(state_vector_prev, P, rho, bcoef_inv(axis_index), mcoef_corrrected, R_ACC, FLT_EPSILON, - &_aid_src_drag.innovation_variance[axis_index], &Kfusion); + &innovation_variance(axis_index), &Kfusion); if (!using_bcoef_y && !using_mcoef) { continue; } } - if (_aid_src_drag.innovation_variance[axis_index] < R_ACC) { + if (innovation_variance(axis_index) < R_ACC) { // calculation is badly conditioned - return; + break; } - // Apply an innovation consistency check with a 5 Sigma threshold - const float innov_gate = 5.f; - setEstimatorAidStatusTestRatio(_aid_src_drag, innov_gate); + const float test_ratio = sq(innovation(axis_index)) / (sq(innov_gate) * innovation_variance(axis_index)); if (_control_status.flags.in_air && _control_status.flags.wind && !_control_status.flags.fake_pos - && PX4_ISFINITE(_aid_src_drag.innovation_variance[axis_index]) && PX4_ISFINITE(_aid_src_drag.innovation[axis_index]) - && (_aid_src_drag.test_ratio[axis_index] < 1.f) + && PX4_ISFINITE(innovation_variance(axis_index)) && PX4_ISFINITE(innovation(axis_index)) + && (test_ratio < 1.f) ) { - if (measurementUpdate(Kfusion, _aid_src_drag.innovation_variance[axis_index], _aid_src_drag.innovation[axis_index])) { + if (measurementUpdate(Kfusion, innovation_variance(axis_index), innovation(axis_index))) { fused[axis_index] = true; } } } + updateEstimatorAidStatus(_aid_src_drag, + drag_sample.time_us, // sample timestamp + observation, // observation + observation_variance, // observation variance + innovation, // innovation + innovation_variance, // innovation variance + innov_gate // gate sigma + ); + if (fused[0] && fused[1]) { _aid_src_drag.fused = true; _aid_src_drag.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index f3330fed8c..8ca41ab607 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -127,54 +127,6 @@ void Ekf::reset() _time_good_vert_accel = 0; _clip_counter = 0; -#if defined(CONFIG_EKF2_BAROMETER) - resetEstimatorAidStatus(_aid_src_baro_hgt); -#endif // CONFIG_EKF2_BAROMETER -#if defined(CONFIG_EKF2_AIRSPEED) - resetEstimatorAidStatus(_aid_src_airspeed); -#endif // CONFIG_EKF2_AIRSPEED -#if defined(CONFIG_EKF2_SIDESLIP) - resetEstimatorAidStatus(_aid_src_sideslip); -#endif // CONFIG_EKF2_SIDESLIP - - resetEstimatorAidStatus(_aid_src_fake_pos); - resetEstimatorAidStatus(_aid_src_fake_hgt); - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - resetEstimatorAidStatus(_aid_src_ev_hgt); - resetEstimatorAidStatus(_aid_src_ev_pos); - resetEstimatorAidStatus(_aid_src_ev_vel); - resetEstimatorAidStatus(_aid_src_ev_yaw); -#endif // CONFIG_EKF2_EXTERNAL_VISION - -#if defined(CONFIG_EKF2_GNSS) - resetEstimatorAidStatus(_aid_src_gnss_hgt); - resetEstimatorAidStatus(_aid_src_gnss_pos); - resetEstimatorAidStatus(_aid_src_gnss_vel); - -# if defined(CONFIG_EKF2_GNSS_YAW) - resetEstimatorAidStatus(_aid_src_gnss_yaw); -# endif // CONFIG_EKF2_GNSS_YAW -#endif // CONFIG_EKF2_GNSS - -#if defined(CONFIG_EKF2_MAGNETOMETER) - resetEstimatorAidStatus(_aid_src_mag_heading); - resetEstimatorAidStatus(_aid_src_mag); -#endif // CONFIG_EKF2_MAGNETOMETER - -#if defined(CONFIG_EKF2_AUXVEL) - resetEstimatorAidStatus(_aid_src_aux_vel); -#endif // CONFIG_EKF2_AUXVEL - -#if defined(CONFIG_EKF2_OPTICAL_FLOW) - resetEstimatorAidStatus(_aid_src_optical_flow); - resetEstimatorAidStatus(_aid_src_terrain_optical_flow); -#endif // CONFIG_EKF2_OPTICAL_FLOW - -#if defined(CONFIG_EKF2_RANGE_FINDER) - resetEstimatorAidStatus(_aid_src_rng_hgt); -#endif // CONFIG_EKF2_RANGE_FINDER - _zero_velocity_update.reset(); } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 9460e9bff3..f058845ee3 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -628,8 +628,6 @@ private: estimator_aid_source3d_s _aid_src_ev_vel{}; estimator_aid_source1d_s _aid_src_ev_yaw{}; - float _ev_yaw_pred_prev{}; ///< previous value of yaw state used by odometry fusion (m) - uint8_t _nb_ev_pos_reset_available{0}; uint8_t _nb_ev_vel_reset_available{0}; uint8_t _nb_ev_yaw_reset_available{0}; @@ -692,9 +690,6 @@ private: #endif // CONFIG_EKF2_BAROMETER #if defined(CONFIG_EKF2_MAGNETOMETER) - float _mag_heading_prev{}; ///< previous value of mag heading (rad) - float _mag_heading_pred_prev{}; ///< previous value of yaw state used by mag heading fusion (rad) - // used by magnetometer fusion mode selection bool _mag_bias_observable{false}; ///< true when there is enough rotation to make magnetometer bias errors observable bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable @@ -755,7 +750,6 @@ private: } // update quaternion states and covariances using an innovation, observation variance and Jacobian vector - bool fuseYaw(estimator_aid_source1d_s &aid_src_status); bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; @@ -763,7 +757,7 @@ private: #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true); + bool fuseMag(VectorState &H, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = false); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians @@ -823,20 +817,24 @@ private: void resetVerticalVelocityToZero(); // horizontal and vertical position aid source - void updateHorizontalPositionAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, const float innov_gate, estimator_aid_source2d_s &aid_src) const; - void updateVerticalPositionAidSrcStatus(const uint64_t &time_us, const float obs, const float obs_var, const float innov_gate, estimator_aid_source1d_s &aid_src) const; + void updateHorizontalPositionAidStatus(estimator_aid_source2d_s &aid_src, const uint64_t &time_us, + const Vector2f &observation, const Vector2f &observation_variance, const float innovation_gate = 1.f) const; + void updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, + const float observation, const float observation_variance, const float innovation_gate = 1.f) const; // 2d & 3d velocity aid source - void updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, const float innov_gate, estimator_aid_source2d_s &aid_src) const; - void updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector3f &obs, const Vector3f &obs_var, const float innov_gate, estimator_aid_source3d_s &aid_src) const; + void updateVelocityAidStatus(estimator_aid_source2d_s &aid_src, const uint64_t &time_us, const Vector2f &observation, + const Vector2f &observation_variance, float innovation_gate = 1.f) const; + void updateVelocityAidStatus(estimator_aid_source3d_s &aid_src, const uint64_t &time_us, const Vector3f &observation, + const Vector3f &observation_variance, float innovation_gate = 1.f) const; // horizontal and vertical position fusion - void fuseHorizontalPosition(estimator_aid_source2d_s &pos_aid_src); - void fuseVerticalPosition(estimator_aid_source1d_s &hgt_aid_src); + bool fuseHorizontalPosition(estimator_aid_source2d_s &pos_aid_src); + bool fuseVerticalPosition(estimator_aid_source1d_s &hgt_aid_src); // 2d & 3d velocity fusion - void fuseVelocity(estimator_aid_source2d_s &vel_aid_src); - void fuseVelocity(estimator_aid_source3d_s &vel_aid_src); + bool fuseVelocity(estimator_aid_source2d_s &vel_aid_src); + bool fuseVelocity(estimator_aid_source3d_s &vel_aid_src); #if defined(CONFIG_EKF2_TERRAIN) // terrain vertical position estimator @@ -1149,88 +1147,179 @@ private: bool _ev_q_error_initialized{false}; #endif // CONFIG_EKF2_EXTERNAL_VISION - void resetEstimatorAidStatus(estimator_aid_source1d_s &status) const + void updateEstimatorAidStatusStateReset(estimator_aid_source1d_s &status, const uint64_t ×tamp_sample, + const float &observation, const float observation_variance = {}) const { - // only bother resetting if timestamp_sample is set - if (status.timestamp_sample != 0) { - status.timestamp_sample = 0; + status.timestamp_sample = timestamp_sample; - // preserve status.time_last_fuse + status.time_last_fuse = _time_delayed_us; - status.observation = 0; - status.observation_variance = 0; + status.observation = observation; + status.observation_variance = observation_variance; - status.innovation = 0; - status.innovation_variance = 0; - status.test_ratio = INFINITY; + status.innovation = 0.f; + status.innovation_filtered = 0.f; + status.innovation_variance = 0.f; - status.innovation_rejected = true; - status.fused = false; - } + status.test_ratio = 0.f; + status.test_ratio_filtered = 0.f; + + status.fused = true; + status.innovation_rejected = false; } - template - void resetEstimatorAidStatus(T &status) const - { - // only bother resetting if timestamp_sample is set - if (status.timestamp_sample != 0) { - status.timestamp_sample = 0; + // bool innovationValid(estimator_aid_source1d_s &status) const + // { + // return (status.time_us != 0) + // && PX4_ISFINITE(status.observation) + // && PX4_ISFINITE(status.innovation) + // && PX4_ISFINITE(status.innovation_variance) + // && (status.innovation_variance > 0.f) + // && (status.observation_variance > 0.f) + // && (status.innovation_variance >= aid_src.observation_variance) + // && !status.innovation_rejected; + // } - // preserve status.time_last_fuse - - for (size_t i = 0; i < (sizeof(status.observation) / sizeof(status.observation[0])); i++) { - status.observation[i] = 0; - status.observation_variance[i] = 0; - - status.innovation[i] = 0; - status.innovation_variance[i] = 0; - status.test_ratio[i] = INFINITY; - } - - status.innovation_rejected = true; - status.fused = false; - } - } - - void setEstimatorAidStatusTestRatio(estimator_aid_source1d_s &status, float innovation_gate) const - { - if (PX4_ISFINITE(status.innovation) - && PX4_ISFINITE(status.innovation_variance) - && (status.innovation_variance > 0.f) - ) { - status.test_ratio = sq(status.innovation) / (sq(innovation_gate) * status.innovation_variance); - status.innovation_rejected = (status.test_ratio > 1.f); - - } else { - status.test_ratio = INFINITY; - status.innovation_rejected = true; - } - } - - template - void setEstimatorAidStatusTestRatio(T &status, float innovation_gate) const + void updateEstimatorAidStatus(estimator_aid_source1d_s &status, const uint64_t ×tamp_sample, + const float &observation, const float &observation_variance, + const float &innovation, const float &innovation_variance, + float innovation_gate = 1.f) const { bool innovation_rejected = false; - for (size_t i = 0; i < (sizeof(status.test_ratio) / sizeof(status.test_ratio[0])); i++) { - if (PX4_ISFINITE(status.innovation[i]) - && PX4_ISFINITE(status.innovation_variance[i]) - && (status.innovation_variance[i] > 0.f) - ) { - status.test_ratio[i] = sq(status.innovation[i]) / (sq(innovation_gate) * status.innovation_variance[i]); + const float dt_s = math::constrain((timestamp_sample - status.timestamp_sample) * 1e-6f, 0.001f, 1.f); - if (status.test_ratio[i] > 1.f) { - innovation_rejected = true; - } + static constexpr float tau = 1.f; + const float alpha = math::constrain(dt_s / (dt_s + tau), 0.f, 1.f); + + const float test_ratio = sq(innovation) / (sq(innovation_gate) * innovation_variance); + + // test_ratio_filtered + if (PX4_ISFINITE(status.test_ratio_filtered)) { + status.test_ratio_filtered += alpha * (matrix::sign(innovation) * test_ratio - status.test_ratio_filtered); + + } else { + // otherwise, init the filtered test ratio + status.test_ratio_filtered = test_ratio; + } + + status.test_ratio = test_ratio; + + status.observation = observation; + status.observation_variance = observation_variance; + + // innovation_filtered + if (PX4_ISFINITE(status.innovation_filtered)) { + status.innovation_filtered += alpha * (innovation - status.innovation_filtered); + + } else { + // otherwise, init the filtered innovation + status.innovation_filtered = innovation; + } + + status.innovation = innovation; + status.innovation_variance = innovation_variance; + + if ((test_ratio > 1.f) + || !PX4_ISFINITE(test_ratio) + || !PX4_ISFINITE(status.innovation) + || !PX4_ISFINITE(status.innovation_variance) + ) { + innovation_rejected = true; + } + + status.timestamp_sample = timestamp_sample; + + // if any of the innovations are rejected, then the overall innovation is rejected + status.innovation_rejected = innovation_rejected; + + // reset + status.fused = false; + } + + template + void updateEstimatorAidStatusStateReset(T &status, const uint64_t ×tamp_sample, + const S &observation, const S observation_variance = {}) const + { + status.timestamp_sample = timestamp_sample; + + status.time_last_fuse = _time_delayed_us; + + for (size_t i = 0; i < (sizeof(status.observation) / sizeof(status.observation[0])); i++) { + status.observation[i] = observation(i); + status.observation_variance[i] = observation_variance(i); + + status.innovation[i] = 0.f; + status.innovation_filtered[i] = 0.f; + status.innovation_variance[i] = 0.f; + + status.test_ratio[i] = 0.f; + status.test_ratio_filtered[i] = 0.f; + } + + status.fused = true; + status.innovation_rejected = false; + } + + template + void updateEstimatorAidStatus(T &status, const uint64_t ×tamp_sample, + const S &observation, const S &observation_variance, + const S &innovation, const S &innovation_variance, + float innovation_gate = 1.f) const + { + bool innovation_rejected = false; + + const float dt_s = math::constrain((timestamp_sample - status.timestamp_sample) * 1e-6f, 0.001f, 1.f); + + static constexpr float tau = 1.f; + const float alpha = math::constrain(dt_s / (dt_s + tau), 0.f, 1.f); + + for (size_t i = 0; i < (sizeof(status.observation) / sizeof(status.observation[0])); i++) { + + const float test_ratio = sq(innovation(i)) / (sq(innovation_gate) * innovation_variance(i)); + + // test_ratio_filtered + if (PX4_ISFINITE(status.test_ratio_filtered[i])) { + status.test_ratio_filtered[i] += alpha * (matrix::sign(innovation(i)) * test_ratio - status.test_ratio_filtered[i]); } else { - status.test_ratio[i] = INFINITY; + // otherwise, init the filtered test ratio + status.test_ratio_filtered[i] = test_ratio; + } + + status.test_ratio[i] = test_ratio; + + status.observation[i] = observation(i); + status.observation_variance[i] = observation_variance(i); + + // innovation_filtered + if (PX4_ISFINITE(status.innovation_filtered[i])) { + status.innovation_filtered[i] += alpha * (innovation(i) - status.innovation_filtered[i]); + + } else { + // otherwise, init the filtered innovation + status.innovation_filtered[i] = innovation(i); + } + + status.innovation[i] = innovation(i); + status.innovation_variance[i] = innovation_variance(i); + + if ((test_ratio > 1.f) + || !PX4_ISFINITE(test_ratio) + || !PX4_ISFINITE(status.innovation[i]) + || !PX4_ISFINITE(status.innovation_variance[i]) + ) { innovation_rejected = true; } } + status.timestamp_sample = timestamp_sample; + // if any of the innovations are rejected, then the overall innovation is rejected status.innovation_rejected = innovation_rejected; + + // reset + status.fused = false; } ZeroGyroUpdate _zero_gyro_update{}; diff --git a/src/modules/ekf2/EKF/ev_control.cpp b/src/modules/ekf2/EKF/ev_control.cpp index 22ac4ec764..f616673d25 100644 --- a/src/modules/ekf2/EKF/ev_control.cpp +++ b/src/modules/ekf2/EKF/ev_control.cpp @@ -68,9 +68,6 @@ void Ekf::controlExternalVisionFusion() _ev_sample_prev = ev_sample; } - // record corresponding yaw state for future EV delta heading innovation (logging only) - _ev_yaw_pred_prev = getEulerYaw(_state.quat_nominal); - } else if ((_control_status.flags.ev_pos || _control_status.flags.ev_vel || _control_status.flags.ev_yaw || _control_status.flags.ev_hgt) && isTimedOut(_ev_sample_prev.time_us, 2 * EV_MAX_INTERVAL)) { diff --git a/src/modules/ekf2/EKF/ev_height_control.cpp b/src/modules/ekf2/EKF/ev_height_control.cpp index c0980a71b3..d3b7123776 100644 --- a/src/modules/ekf2/EKF/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/ev_height_control.cpp @@ -77,19 +77,21 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com float measurement_var = math::max(pos_cov(2, 2), sq(_params.ev_pos_noise), sq(0.01f)); #if defined(CONFIG_EKF2_GNSS) + // increase minimum variance if GPS active if (_control_status.flags.gps_hgt) { measurement_var = math::max(measurement_var, sq(_params.gps_pos_noise)); } + #endif // CONFIG_EKF2_GNSS const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); - updateVerticalPositionAidSrcStatus(ev_sample.time_us, - measurement - bias_est.getBias(), - measurement_var + bias_est.getBiasVar(), - math::max(_params.ev_pos_innov_gate, 1.f), - aid_src); + updateVerticalPositionAidStatus(aid_src, + ev_sample.time_us, + measurement - bias_est.getBias(), // observation + measurement_var + bias_est.getBiasVar(), // observation variance + math::max(_params.ev_pos_innov_gate, 1.f)); // gate sigma // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -108,7 +110,6 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com if (_control_status.flags.ev_hgt) { if (continuing_conditions_passing) { if (ev_reset) { - if (quality_sufficient) { ECL_INFO("reset to %s", AID_SRC_NAME); @@ -145,6 +146,7 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com _information_events.flags.reset_hgt_to_ev = true; resetVerticalPositionTo(measurement - bias_est.getBias(), measurement_var); bias_est.setBias(-_state.pos(2) + measurement); + updateEstimatorAidStatusStateReset(aid_src, ev_sample.time_us, measurement - bias_est.getBias()); // reset vertical velocity if (ev_sample.vel.isAllFinite() && (_params.ev_ctrl & static_cast(EvCtrl::VEL))) { @@ -195,6 +197,7 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, const bool com ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME); _information_events.flags.reset_hgt_to_ev = true; resetVerticalPositionTo(measurement, measurement_var); + updateEstimatorAidStatusStateReset(aid_src, ev_sample.time_us, measurement, measurement_var); _height_sensor_ref = HeightSensor::EV; bias_est.reset(); @@ -220,7 +223,6 @@ void Ekf::stopEvHgtFusion() } _ev_hgt_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_ev_hgt); _control_status.flags.ev_hgt = false; } diff --git a/src/modules/ekf2/EKF/ev_pos_control.cpp b/src/modules/ekf2/EKF/ev_pos_control.cpp index 3f6027400a..86081e67f0 100644 --- a/src/modules/ekf2/EKF/ev_pos_control.cpp +++ b/src/modules/ekf2/EKF/ev_pos_control.cpp @@ -126,12 +126,14 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common } #if defined(CONFIG_EKF2_GNSS) + // increase minimum variance if GPS active (position reference) if (_control_status.flags.gps) { for (int i = 0; i < 2; i++) { pos_cov(i, i) = math::max(pos_cov(i, i), sq(_params.gps_pos_noise)); } } + #endif // CONFIG_EKF2_GNSS const Vector2f measurement{pos(0), pos(1)}; @@ -155,11 +157,11 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common } } - updateHorizontalPositionAidSrcStatus(ev_sample.time_us, - measurement - _ev_pos_b_est.getBias(), // observation - measurement_var + _ev_pos_b_est.getBiasVar(), // observation variance - math::max(_params.ev_pos_innov_gate, 1.f), // innovation gate - aid_src); + updateHorizontalPositionAidStatus(aid_src, + ev_sample.time_us, + measurement - _ev_pos_b_est.getBias(), // observation + measurement_var + _ev_pos_b_est.getBiasVar(), // observation variance + math::max(_params.ev_pos_innov_gate, 1.f)); // gate sigma // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -177,7 +179,6 @@ void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, const bool common && continuing_conditions_passing; if (_control_status.flags.ev_pos) { - if (continuing_conditions_passing) { const bool bias_estimator_change = (bias_fusion_was_active != _ev_pos_b_est.fusionActive()); const bool reset = ev_reset || yaw_alignment_changed || bias_estimator_change; @@ -221,7 +222,8 @@ void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurem _control_status.flags.ev_pos = true; } -void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src) +void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, + bool reset, estimator_aid_source2d_s &aid_src) { if (reset) { @@ -297,8 +299,6 @@ void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measure void Ekf::stopEvPosFusion() { if (_control_status.flags.ev_pos) { - resetEstimatorAidStatus(_aid_src_ev_pos); - _control_status.flags.ev_pos = false; } } diff --git a/src/modules/ekf2/EKF/ev_vel_control.cpp b/src/modules/ekf2/EKF/ev_vel_control.cpp index aff345ac11..98c1947097 100644 --- a/src/modules/ekf2/EKF/ev_vel_control.cpp +++ b/src/modules/ekf2/EKF/ev_vel_control.cpp @@ -107,12 +107,14 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common } #if defined(CONFIG_EKF2_GNSS) + // increase minimum variance if GPS active (position reference) if (_control_status.flags.gps) { for (int i = 0; i < 2; i++) { vel_cov(i, i) = math::max(vel_cov(i, i), sq(_params.gps_vel_noise)); } } + #endif // CONFIG_EKF2_GNSS const Vector3f measurement{vel}; @@ -125,11 +127,11 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common const bool measurement_valid = measurement.isAllFinite() && measurement_var.isAllFinite(); - updateVelocityAidSrcStatus(ev_sample.time_us, - measurement, // observation - measurement_var, // observation variance - math::max(_params.ev_vel_innov_gate, 1.f), // innovation gate - aid_src); + updateVelocityAidStatus(aid_src, + ev_sample.time_us, // sample timestamp + measurement, // observation + measurement_var, // observation variance + math::max(_params.ev_vel_innov_gate, 1.f)); // innovation gate if (!measurement_valid) { continuing_conditions_passing = false; @@ -140,7 +142,6 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common && ((Vector3f(aid_src.test_ratio).max() < 0.1f) || !isHorizontalAidingActive()); if (_control_status.flags.ev_vel) { - if (continuing_conditions_passing) { if ((ev_reset && isOnlyActiveSourceOfHorizontalAiding(_control_status.flags.ev_vel)) || yaw_alignment_changed) { @@ -149,6 +150,7 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common ECL_INFO("reset to %s", AID_SRC_NAME); _information_events.flags.reset_vel_to_vision = true; resetVelocityTo(measurement, measurement_var); + updateEstimatorAidStatusStateReset(aid_src, ev_sample.time_us, measurement, measurement_var); aid_src.time_last_fuse = _time_delayed_us; } else { @@ -174,7 +176,7 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common _information_events.flags.reset_vel_to_vision = true; ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetVelocityTo(measurement, measurement_var); - aid_src.time_last_fuse = _time_delayed_us; + updateEstimatorAidStatusStateReset(aid_src, ev_sample.time_us, measurement, measurement_var); if (_control_status.flags.in_air) { _nb_ev_vel_reset_available--; @@ -205,9 +207,12 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common if (starting_conditions_passing) { // activate fusion, only reset if necessary if (!isHorizontalAidingActive() || yaw_alignment_changed) { - ECL_INFO("starting %s fusion, resetting velocity to (%.3f, %.3f, %.3f)", AID_SRC_NAME, (double)measurement(0), (double)measurement(1), (double)measurement(2)); + ECL_INFO("starting %s fusion, resetting velocity to (%.3f, %.3f, %.3f)", AID_SRC_NAME, + (double)measurement(0), (double)measurement(1), (double)measurement(2)); + _information_events.flags.reset_vel_to_vision = true; resetVelocityTo(measurement, measurement_var); + updateEstimatorAidStatusStateReset(aid_src, ev_sample.time_us, measurement, measurement_var); } else { ECL_INFO("starting %s fusion", AID_SRC_NAME); @@ -225,7 +230,6 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, const bool common void Ekf::stopEvVelFusion() { if (_control_status.flags.ev_vel) { - resetEstimatorAidStatus(_aid_src_ev_vel); _control_status.flags.ev_vel = false; } diff --git a/src/modules/ekf2/EKF/ev_yaw_control.cpp b/src/modules/ekf2/EKF/ev_yaw_control.cpp index 3afb3b78fc..438d2bcc60 100644 --- a/src/modules/ekf2/EKF/ev_yaw_control.cpp +++ b/src/modules/ekf2/EKF/ev_yaw_control.cpp @@ -43,11 +43,22 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common { static constexpr const char *AID_SRC_NAME = "EV yaw"; - resetEstimatorAidStatus(aid_src); - aid_src.timestamp_sample = ev_sample.time_us; - aid_src.observation = getEulerYaw(ev_sample.quat); - aid_src.observation_variance = math::max(ev_sample.orientation_var(2), _params.ev_att_noise, sq(0.01f)); - aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation); + float obs = getEulerYaw(ev_sample.quat); + float obs_var = math::max(ev_sample.orientation_var(2), _params.ev_att_noise, sq(0.01f)); + + float innov = wrap_pi(getEulerYaw(_R_to_earth) - obs); + float innov_var = 0.f; + + VectorState H_YAW; + computeYawInnovVarAndH(obs_var, innov_var, H_YAW); + + updateEstimatorAidStatus(aid_src, + ev_sample.time_us, // sample timestamp + obs, // observation + obs_var, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // gate sigma if (ev_reset) { _control_status.flags.ev_yaw_fault = false; @@ -65,10 +76,6 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common && (ev_sample.pos_frame != PositionFrame::LOCAL_FRAME_NED) ) { continuing_conditions_passing = false; - - // use delta yaw for innovation logging - aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _ev_yaw_pred_prev) - - wrap_pi(getEulerYaw(ev_sample.quat) - getEulerYaw(_ev_sample_prev.quat))); } const bool starting_conditions_passing = common_starting_conditions_passing @@ -94,7 +101,7 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common } } else if (quality_sufficient) { - fuseYaw(aid_src); + fuseYaw(aid_src, H_YAW); } else { aid_src.innovation_rejected = true; @@ -140,7 +147,7 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common // activate fusion if (ev_sample.pos_frame == PositionFrame::LOCAL_FRAME_NED) { - if (_control_status.flags.yaw_align) { + if (_control_status.flags.yaw_align && fuseYaw(aid_src, H_YAW)) { ECL_INFO("starting %s fusion", AID_SRC_NAME); } else { @@ -160,6 +167,7 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common // reset yaw to EV resetQuatStateYaw(aid_src.observation, aid_src.observation_variance); + // TODO: update aid_src? aid_src.time_last_fuse = _time_delayed_us; _information_events.flags.starting_vision_yaw_fusion = true; @@ -178,7 +186,6 @@ void Ekf::stopEvYawFusion() { #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_yaw) { - resetEstimatorAidStatus(_aid_src_ev_yaw); _control_status.flags.ev_yaw = false; } diff --git a/src/modules/ekf2/EKF/fake_height_control.cpp b/src/modules/ekf2/EKF/fake_height_control.cpp index 8b7eba5664..4ecb5b5325 100644 --- a/src/modules/ekf2/EKF/fake_height_control.cpp +++ b/src/modules/ekf2/EKF/fake_height_control.cpp @@ -51,8 +51,7 @@ void Ekf::controlFakeHgtFusion() const float obs_var = sq(_params.pos_noaid_noise); const float innov_gate = 3.f; - updateVerticalPositionAidSrcStatus(_time_delayed_us, _last_known_pos(2), obs_var, innov_gate, aid_src); - + updateVerticalPositionAidStatus(aid_src, _time_delayed_us, _last_known_pos(2), obs_var, innov_gate); const bool continuing_conditions_passing = !isVerticalAidingActive(); const bool starting_conditions_passing = continuing_conditions_passing @@ -113,7 +112,5 @@ void Ekf::stopFakeHgtFusion() if (_control_status.flags.fake_hgt) { ECL_INFO("stop fake height fusion"); _control_status.flags.fake_hgt = false; - - resetEstimatorAidStatus(_aid_src_fake_hgt); } } diff --git a/src/modules/ekf2/EKF/fake_pos_control.cpp b/src/modules/ekf2/EKF/fake_pos_control.cpp index 4962cd55fc..6930a4d7fb 100644 --- a/src/modules/ekf2/EKF/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/fake_pos_control.cpp @@ -65,8 +65,11 @@ void Ekf::controlFakePosFusion() const float innov_gate = 3.f; - updateHorizontalPositionAidSrcStatus(_time_delayed_us, Vector2f(_last_known_pos), obs_var, innov_gate, aid_src); - + updateHorizontalPositionAidStatus(aid_src, + _time_delayed_us, + Vector2f(_last_known_pos), // observation + obs_var, // observation variance + innov_gate); const bool continuing_conditions_passing = !isHorizontalAidingActive(); const bool starting_conditions_passing = continuing_conditions_passing @@ -77,8 +80,8 @@ void Ekf::controlFakePosFusion() // always protect against extreme values that could result in a NaN if ((aid_src.test_ratio[0] < sq(100.0f / innov_gate)) - && (aid_src.test_ratio[1] < sq(100.0f / innov_gate)) - ) { + && (aid_src.test_ratio[1] < sq(100.0f / innov_gate)) + ) { fuseHorizontalPosition(aid_src); } @@ -128,7 +131,5 @@ void Ekf::stopFakePosFusion() if (_control_status.flags.fake_pos) { ECL_INFO("stop fake position fusion"); _control_status.flags.fake_pos = false; - - resetEstimatorAidStatus(_aid_src_fake_pos); } } diff --git a/src/modules/ekf2/EKF/gnss_height_control.cpp b/src/modules/ekf2/EKF/gnss_height_control.cpp index 0ea8e932c3..8f64f35de1 100644 --- a/src/modules/ekf2/EKF/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/gnss_height_control.cpp @@ -63,16 +63,14 @@ void Ekf::controlGnssHeightFusion(const gpsSample &gps_sample) const float measurement = gps_sample.hgt - getEkfGlobalOriginAltitude(); const float measurement_var = sq(noise); - const float innov_gate = math::max(_params.gps_pos_innov_gate, 1.f); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); // GNSS position, vertical position GNSS measurement has opposite sign to earth z axis - updateVerticalPositionAidSrcStatus(gps_sample.time_us, - -(measurement - bias_est.getBias()), - measurement_var + bias_est.getBiasVar(), - innov_gate, - aid_src); + updateVerticalPositionAidStatus(aid_src, + gps_sample.time_us, + -(measurement - bias_est.getBias()), + measurement_var + bias_est.getBiasVar(), + math::max(_params.gps_pos_innov_gate, 1.f)); const bool gps_checks_passing = isTimedOut(_last_gps_fail_us, (uint64_t)5e6); const bool gps_checks_failing = isTimedOut(_last_gps_pass_us, (uint64_t)5e6); @@ -173,7 +171,6 @@ void Ekf::stopGpsHgtFusion() } _gps_hgt_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_gnss_hgt); _control_status.flags.gps_hgt = false; } diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index 6e8d3892aa..6185ee93f6 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -92,13 +92,13 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) // GNSS velocity const Vector3f velocity{gps_sample.vel}; - const float vel_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise)); + const float vel_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise, 0.01f)); const Vector3f vel_obs_var(vel_var, vel_var, vel_var * sq(1.5f)); - updateVelocityAidSrcStatus(gps_sample.time_us, - velocity, // observation - vel_obs_var, // observation variance - math::max(_params.gps_vel_innov_gate, 1.f), // innovation gate - _aid_src_gnss_vel); + updateVelocityAidStatus(_aid_src_gnss_vel, + gps_sample.time_us, // sample timestamp + velocity, // observation + vel_obs_var, // observation variance + math::max(_params.gps_vel_innov_gate, 1.f)); // innovation gate const bool gnss_vel_enabled = (_params.gnss_ctrl & static_cast(GnssCtrl::VEL)); // GNSS position @@ -114,13 +114,13 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } } - const float pos_var = sq(pos_noise); + const float pos_var = math::max(sq(pos_noise), sq(0.01f)); const Vector2f pos_obs_var(pos_var, pos_var); - updateHorizontalPositionAidSrcStatus(gps_sample.time_us, - position, // observation - pos_obs_var, // observation variance - math::max(_params.gps_pos_innov_gate, 1.f), // innovation gate - _aid_src_gnss_pos); + updateHorizontalPositionAidStatus(_aid_src_gnss_pos, + gps_sample.time_us, // sample timestamp + position, // observation + pos_obs_var, // observation variance + math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate const bool gnss_pos_enabled = (_params.gnss_ctrl & static_cast(GnssCtrl::HPOS)); // Determine if we should use GPS aiding for velocity and horizontal position @@ -399,7 +399,6 @@ void Ekf::stopGpsYawFusion() if (_control_status.flags.gps_yaw) { _control_status.flags.gps_yaw = false; - resetEstimatorAidStatus(_aid_src_gnss_yaw); // Before takeoff, we do not want to continue to rely on the current heading // if we had to stop the fusion @@ -418,8 +417,6 @@ void Ekf::stopGpsFusion() { if (_control_status.flags.gps) { ECL_INFO("stopping GPS position and velocity fusion"); - resetEstimatorAidStatus(_aid_src_gnss_pos); - resetEstimatorAidStatus(_aid_src_gnss_vel); _control_status.flags.gps = false; } diff --git a/src/modules/ekf2/EKF/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/gps_yaw_fusion.cpp index d02c07f994..4210c94ce8 100644 --- a/src/modules/ekf2/EKF/gps_yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/gps_yaw_fusion.cpp @@ -50,11 +50,6 @@ void Ekf::updateGpsYaw(const gpsSample &gps_sample) { if (PX4_ISFINITE(gps_sample.yaw)) { - auto &gnss_yaw = _aid_src_gnss_yaw; - resetEstimatorAidStatus(gnss_yaw); - - // initially populate for estimator_aid_src_gnss_yaw logging - // calculate the observed yaw angle of antenna array, converting a from body to antenna yaw measurement const float measured_hdg = wrap_pi(gps_sample.yaw + _gps_yaw_offset); @@ -68,15 +63,13 @@ void Ekf::updateGpsYaw(const gpsSample &gps_sample) sym::ComputeGnssYawPredInnovVarAndH(_state.vector(), P, _gps_yaw_offset, R_YAW, FLT_EPSILON, &heading_pred, &heading_innov_var, &H); } - gnss_yaw.observation = measured_hdg; - gnss_yaw.observation_variance = R_YAW; - gnss_yaw.innovation = wrap_pi(heading_pred - measured_hdg); - gnss_yaw.innovation_variance = heading_innov_var; - - gnss_yaw.timestamp_sample = gps_sample.time_us; - - const float innov_gate = math::max(_params.heading_innov_gate, 1.0f); - setEstimatorAidStatusTestRatio(gnss_yaw, innov_gate); + updateEstimatorAidStatus(_aid_src_gnss_yaw, + gps_sample.time_us, // sample timestamp + measured_hdg, // observation + R_YAW, // observation variance + wrap_pi(heading_pred - measured_hdg), // innovation + heading_innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // gate sigma } } diff --git a/src/modules/ekf2/EKF/gravity_fusion.cpp b/src/modules/ekf2/EKF/gravity_fusion.cpp index 13ae1112c6..68bfcc82dc 100644 --- a/src/modules/ekf2/EKF/gravity_fusion.cpp +++ b/src/modules/ekf2/EKF/gravity_fusion.cpp @@ -55,7 +55,7 @@ void Ekf::controlGravityFusion(const imuSample &imu) // get raw accelerometer reading at delayed horizon and expected measurement noise (gaussian) const Vector3f measurement = imu.delta_vel / imu.delta_vel_dt - getAccelBias(); - const float measurement_var = sq(_params.gravity_noise); + const float measurement_var = math::max(sq(_params.gravity_noise), sq(0.01f)); // calculate kalman gains and innovation variances Vector3f innovation; // innovation of the last gravity fusion observation (m/s**2) @@ -66,19 +66,13 @@ void Ekf::controlGravityFusion(const imuSample &imu) &innovation, &innovation_variance, &Kx, &Ky, &Kz); // fill estimator aid source status - resetEstimatorAidStatus(_aid_src_gravity); - _aid_src_gravity.timestamp_sample = imu.time_us; - measurement.copyTo(_aid_src_gravity.observation); - - for (auto &var : _aid_src_gravity.observation_variance) { - var = measurement_var; - } - - innovation.copyTo(_aid_src_gravity.innovation); - innovation_variance.copyTo(_aid_src_gravity.innovation_variance); - - float innovation_gate = 1.f; - setEstimatorAidStatusTestRatio(_aid_src_gravity, innovation_gate); + updateEstimatorAidStatus(_aid_src_gravity, + imu.time_us, // sample timestamp + measurement, // observation + Vector3f{measurement_var, measurement_var, measurement_var}, // observation variance + innovation, // innovation + innovation_variance // innovation variance + ); const bool accel_clipping = imu.delta_vel_clipping[0] || imu.delta_vel_clipping[1] || imu.delta_vel_clipping[2]; diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp index 738441cf27..f99b7db94b 100644 --- a/src/modules/ekf2/EKF/mag_3d_control.cpp +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -38,12 +38,36 @@ #include "ekf.h" +#include "python/ekf_derivation/generated/compute_mag_innov_innov_var_and_hx.h" + void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source3d_s &aid_src) { static constexpr const char *AID_SRC_NAME = "mag"; - resetEstimatorAidStatus(aid_src); + // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations + const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); + + // calculate intermediate variables used for X axis innovation variance, observation Jacobians and Kalman gains + const auto state_vector = _state.vector(); + Vector3f innov; + Vector3f innov_var; + VectorState H; + + sym::ComputeMagInnovInnovVarAndHx(state_vector, P, mag_sample.mag, R_MAG, FLT_EPSILON, &innov, &innov_var, &H); + + // do not use the synthesized measurement for the magnetomter Z component for 3D fusion + if (_control_status.flags.synthetic_mag_z) { + innov(2) = 0.0f; + } + + updateEstimatorAidStatus(aid_src, + mag_sample.time_us, // sample timestamp + mag_sample.mag, // observation + Vector3f(R_MAG, R_MAG, R_MAG), // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.mag_innov_gate, 1.f)); // gate sigma const bool wmm_updated = (_wmm_gps_time_last_set > aid_src.time_last_fuse); @@ -105,14 +129,14 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // states for the first few observations. fuseDeclination(0.02f); _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, aid_src, false); + fuseMag(H, aid_src); } else { // The normal sequence is to fuse the magnetometer data first before fusing // declination angle at a higher uncertainty to allow some learning of // declination angle over time. const bool update_all_states = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, aid_src, update_all_states); + fuseMag(H, aid_src, update_all_states); if (_control_status.flags.mag_dec) { fuseDeclination(0.5f); @@ -127,7 +151,7 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star // Data seems good, attempt a reset (mag states only unless mag_3D currently active) ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); - aid_src.time_last_fuse = _time_delayed_us; + updateEstimatorAidStatusStateReset(aid_src, mag_sample.time_us, _mag_lpf.getState()); if (_control_status.flags.in_air) { _nb_mag_3d_reset_available--; @@ -174,6 +198,7 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star bool reset_heading = !_control_status.flags.yaw_align; resetMagStates(_mag_lpf.getState(), reset_heading); + updateEstimatorAidStatusStateReset(aid_src, mag_sample.time_us, _mag_lpf.getState()); if (reset_heading) { _control_status.flags.yaw_align = true; @@ -181,7 +206,7 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star } else { ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, aid_src, false); + fuseMag(H, aid_src); } aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/mag_fusion.cpp index 1dc2f31c3b..29bc74548a 100644 --- a/src/modules/ekf2/EKF/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/mag_fusion.cpp @@ -51,45 +51,14 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states) +bool Ekf::fuseMag(VectorState& H, estimator_aid_source3d_s &aid_src_mag, bool update_all_states) { - // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations - const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); - // calculate intermediate variables used for X axis innovation variance, observation Jacobians and Kalman gains - Vector3f mag_innov; - Vector3f innov_var; - // Observation jacobian and Kalman gain vectors - VectorState H; - const auto state_vector = _state.vector(); - sym::ComputeMagInnovInnovVarAndHx(state_vector, P, mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); - - // do not use the synthesized measurement for the magnetomter Z component for 3D fusion - if (_control_status.flags.synthetic_mag_z) { - mag_innov(2) = 0.0f; - } - - for (int i = 0; i < 3; i++) { - aid_src_mag.observation[i] = mag(i) - _state.mag_B(i); - aid_src_mag.observation_variance[i] = R_MAG; - aid_src_mag.innovation[i] = mag_innov(i); - aid_src_mag.innovation_variance[i] = innov_var(i); - } - - const float innov_gate = math::max(_params.mag_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(aid_src_mag, innov_gate); - - if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src_mag.innovation_variance[0] < aid_src_mag.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src_mag.innovation_variance[1] < aid_src_mag.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src_mag.innovation_variance[2] < aid_src_mag.observation_variance[2]); - - } else { - _fault_status.flags.bad_mag_x = false; - _fault_status.flags.bad_mag_y = false; - _fault_status.flags.bad_mag_z = false; - } + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + _fault_status.flags.bad_mag_x = (aid_src_mag.innovation_variance[0] < aid_src_mag.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src_mag.innovation_variance[1] < aid_src_mag.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src_mag.innovation_variance[2] < aid_src_mag.observation_variance[2]); // Perform an innovation consistency check and report the result _innov_check_fail_status.flags.reject_mag_x = (aid_src_mag.test_ratio[0] > 1.f); @@ -99,17 +68,19 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo const char *numerical_error_covariance_reset_string = "numerical error - covariance reset"; // check innovation variances for being badly conditioned - if (innov_var.min() < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); + for (uint8_t index = 0; index < 3; index++) { + if (aid_src_mag.innovation_variance[index] < aid_src_mag.observation_variance[index]) { + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + // we need to re-initialise covariances and abort this fusion step + if (update_all_states) { + resetQuatCov(_params.mag_heading_noise); + } + + resetMagCov(); + + ECL_ERR("mag %s", numerical_error_covariance_reset_string); + return false; } - - resetMagCov(); - - ECL_ERR("mag %s", numerical_error_covariance_reset_string); - return false; } // if any axis fails, abort the mag fusion @@ -117,6 +88,8 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo return false; } + const auto state_vector = _state.vector(); + bool fused[3] {false, false, false}; // update the states and covariance using sequential fusion of the magnetometer components @@ -127,12 +100,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); + sym::ComputeMagYInnovVarAndH(state_vector, P, aid_src_mag.observation_variance[index], FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); + aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - aid_src_mag.observation[index]; - if (aid_src_mag.innovation_variance[index] < R_MAG) { + if (aid_src_mag.innovation_variance[index] < aid_src_mag.observation_variance[index]) { // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned _fault_status.flags.bad_mag_y = true; @@ -155,12 +128,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); + sym::ComputeMagZInnovVarAndH(state_vector, P, aid_src_mag.observation_variance[index], FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); + aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - aid_src_mag.observation[index]; - if (aid_src_mag.innovation_variance[index] < R_MAG) { + if (aid_src_mag.innovation_variance[index] < aid_src_mag.observation_variance[index]) { // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned _fault_status.flags.bad_mag_z = true; diff --git a/src/modules/ekf2/EKF/mag_heading_control.cpp b/src/modules/ekf2/EKF/mag_heading_control.cpp index 612474937e..c68e656450 100644 --- a/src/modules/ekf2/EKF/mag_heading_control.cpp +++ b/src/modules/ekf2/EKF/mag_heading_control.cpp @@ -61,19 +61,24 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common const float declination = getMagDeclination(); const float measured_hdg = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + declination; - resetEstimatorAidStatus(aid_src); - aid_src.observation = measured_hdg; - aid_src.observation_variance = math::max(sq(_params.mag_heading_noise), sq(0.01f)); + float obs_var = math::max(sq(_params.mag_heading_noise), sq(0.01f)); + float innov_var = 0.f; + + VectorState H_YAW; + computeYawInnovVarAndH(obs_var, innov_var, H_YAW); + + updateEstimatorAidStatus(aid_src, + mag_sample.time_us, // sample timestamp + measured_hdg, // observation + obs_var, // observation variance + wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation), // innovation + innov_var, // innovation variance + math::max(_params.heading_innov_gate, 1.f)); // gate sigma if (_control_status.flags.yaw_align) { - // mag heading - aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation); _mag_heading_innov_lpf.update(aid_src.innovation); } else { - // mag heading delta (logging only) - aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _mag_heading_pred_prev) - - wrap_pi(measured_hdg - _mag_heading_prev)); _mag_heading_innov_lpf.reset(0.f); } @@ -84,7 +89,7 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) && _control_status.flags.tilt_align && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) && !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed && !_control_status.flags.ev_yaw @@ -115,10 +120,9 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common } resetMagHeading(_mag_lpf.getState()); - aid_src.time_last_fuse = _time_delayed_us; + updateEstimatorAidStatusStateReset(aid_src, mag_sample.time_us, getEulerYaw(_R_to_earth), obs_var); } else { - VectorState H_YAW; computeYawInnovVarAndH(aid_src.observation_variance, aid_src.innovation_variance, H_YAW); if ((aid_src.innovation_variance - aid_src.observation_variance) > sq(_params.mag_heading_noise / 2.f)) { @@ -174,20 +178,20 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common if (!_control_status.flags.yaw_align) { // reset heading resetMagHeading(_mag_lpf.getState()); + updateEstimatorAidStatusStateReset(aid_src, mag_sample.time_us, getEulerYaw(_R_to_earth), obs_var); _control_status.flags.yaw_align = true; } _control_status.flags.mag_hdg = true; + aid_src.time_last_fuse = _time_delayed_us; + aid_src.fused = true; + aid_src.innovation_rejected = false; _nb_mag_heading_reset_available = 1; } } - // record corresponding mag heading and yaw state for future mag heading delta heading innovation (logging only) - _mag_heading_prev = measured_hdg; - _mag_heading_pred_prev = getEulerYaw(_state.quat_nominal); - _mag_heading_last_declination = getMagDeclination(); } @@ -195,7 +199,6 @@ void Ekf::stopMagHdgFusion() { if (_control_status.flags.mag_hdg) { ECL_INFO("stopping mag heading fusion"); - resetEstimatorAidStatus(_aid_src_mag_heading); _control_status.flags.mag_hdg = false; diff --git a/src/modules/ekf2/EKF/optflow_fusion.cpp b/src/modules/ekf2/EKF/optflow_fusion.cpp index 626f0917cd..b843e2ae97 100644 --- a/src/modules/ekf2/EKF/optflow_fusion.cpp +++ b/src/modules/ekf2/EKF/optflow_fusion.cpp @@ -50,9 +50,6 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) { - resetEstimatorAidStatus(aid_src); - aid_src.timestamp_sample = _flow_sample_delayed.time_us; - const Vector2f vel_body = predictFlowVelBody(); const float range = predictFlowRange(); @@ -66,24 +63,26 @@ void Ekf::updateOptFlow(estimator_aid_source2d_s &aid_src) _flow_vel_body(1) = opt_flow_rate(0) * range; _flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f)); - aid_src.observation[0] = opt_flow_rate(0); // flow around the X axis - aid_src.observation[1] = opt_flow_rate(1); // flow around the Y axis - - aid_src.innovation[0] = (vel_body(1) / range) - aid_src.observation[0]; - aid_src.innovation[1] = (-vel_body(0) / range) - aid_src.observation[1]; + Vector2f innovation{ + (vel_body(1) / range) - opt_flow_rate(0), + (-vel_body(0) / range) - opt_flow_rate(1) + }; // calculate the optical flow observation variance const float R_LOS = calcOptFlowMeasVar(_flow_sample_delayed); - aid_src.observation_variance[0] = R_LOS; - aid_src.observation_variance[1] = R_LOS; Vector2f innov_var; VectorState H; sym::ComputeFlowXyInnovVarAndHx(_state.vector(), P, range, R_LOS, FLT_EPSILON, &innov_var, &H); - innov_var.copyTo(aid_src.innovation_variance); // run the innovation consistency check and record result - setEstimatorAidStatusTestRatio(aid_src, math::max(_params.flow_innov_gate, 1.f)); + updateEstimatorAidStatus(aid_src, + _flow_sample_delayed.time_us, // sample timestamp + opt_flow_rate, // observation + Vector2f{R_LOS, R_LOS}, // observation variance + innovation, // innovation + innov_var, // innovation variance + _params.flow_innov_gate); // gate sigma } void Ekf::fuseOptFlow() @@ -99,19 +98,24 @@ void Ekf::fuseOptFlow() Vector2f innov_var; VectorState H; sym::ComputeFlowXyInnovVarAndHx(state_vector, P, range, R_LOS, FLT_EPSILON, &innov_var, &H); - innov_var.copyTo(_aid_src_optical_flow.innovation_variance); - if ((_aid_src_optical_flow.innovation_variance[0] < R_LOS) - || (_aid_src_optical_flow.innovation_variance[1] < R_LOS)) { + // TODO: do we recompute the filtered test ratio? + + // updateEstimatorAidStatus(_aid_src_optical_flow, + // _flow_sample_delayed.time_us, // sample timestamp + // opt_flow_rate, // observation + // Vector2f{R_LOS, R_LOS}, // observation variance + // innovation, // innovation + // innov_var, // innovation variance + // _params.flow_innov_gate); // gate sigma + + if ((innov_var(0) < R_LOS) || (innov_var(1) < R_LOS)) { // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); initialiseCovariance(); return; } - // run the innovation consistency check and record result - setEstimatorAidStatusTestRatio(_aid_src_optical_flow, math::max(_params.flow_innov_gate, 1.f)); - _innov_check_fail_status.flags.reject_optflow_X = (_aid_src_optical_flow.test_ratio[0] > 1.f); _innov_check_fail_status.flags.reject_optflow_Y = (_aid_src_optical_flow.test_ratio[1] > 1.f); diff --git a/src/modules/ekf2/EKF/optical_flow_control.cpp b/src/modules/ekf2/EKF/optical_flow_control.cpp index f8218e883b..64f4d14607 100644 --- a/src/modules/ekf2/EKF/optical_flow_control.cpp +++ b/src/modules/ekf2/EKF/optical_flow_control.cpp @@ -160,8 +160,6 @@ void Ekf::stopFlowFusion() if (_control_status.flags.opt_flow) { ECL_INFO("stopping optical flow fusion"); _control_status.flags.opt_flow = false; - - resetEstimatorAidStatus(_aid_src_optical_flow); } } diff --git a/src/modules/ekf2/EKF/range_height_control.cpp b/src/modules/ekf2/EKF/range_height_control.cpp index 8fede499e5..502ba0bcb4 100644 --- a/src/modules/ekf2/EKF/range_height_control.cpp +++ b/src/modules/ekf2/EKF/range_height_control.cpp @@ -64,13 +64,14 @@ void Ekf::controlRangeHeightFusion() if (_control_status.flags.in_air) { const bool horizontal_motion = _control_status.flags.fixed_wing - || (sq(_state.vel(0)) + sq(_state.vel(1)) > fmaxf(P.trace<2>(State::vel.idx), 0.1f)); + || (sq(_state.vel(0)) + sq(_state.vel(1)) > fmaxf(P.trace<2>(State::vel.idx), 0.1f)); const float dist_dependant_var = sq(_params.range_noise_scaler * _range_sensor.getDistBottom()); const float var = sq(_params.range_noise) + dist_dependant_var; _rng_consistency_check.setGate(_params.range_kin_consistency_gate); - _rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2), P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, _time_delayed_us); + _rng_consistency_check.update(_range_sensor.getDistBottom(), math::max(var, 0.001f), _state.vel(2), + P(State::vel.idx + 2, State::vel.idx + 2), horizontal_motion, _time_delayed_us); } } else { @@ -101,16 +102,14 @@ void Ekf::controlRangeHeightFusion() const float measurement = math::max(_range_sensor.getDistBottom(), _params.rng_gnd_clearance); const float measurement_var = sq(_params.range_noise) + sq(_params.range_noise_scaler * _range_sensor.getDistBottom()); - const float innov_gate = math::max(_params.range_innov_gate, 1.f); - const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); // vertical position innovation - baro measurement has opposite sign to earth z axis - updateVerticalPositionAidSrcStatus(_range_sensor.getSampleAddress()->time_us, - -(measurement - bias_est.getBias()), - measurement_var + bias_est.getBiasVar(), - innov_gate, - aid_src); + updateVerticalPositionAidStatus(aid_src, + _range_sensor.getSampleAddress()->time_us, + -(measurement - bias_est.getBias()), + measurement_var + bias_est.getBiasVar(), + math::max(_params.range_innov_gate, 1.f)); // update the bias estimator before updating the main filter but after // using its current state to compute the vertical position innovation @@ -121,8 +120,10 @@ void Ekf::controlRangeHeightFusion() } // determine if we should use height aiding - const bool do_conditional_range_aid = (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) && isConditionalRangeAidSuitable(); - const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) || do_conditional_range_aid) + const bool do_conditional_range_aid = (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) + && isConditionalRangeAidSuitable(); + const bool continuing_conditions_passing = ((_params.rng_ctrl == static_cast(RngCtrl::ENABLED)) + || do_conditional_range_aid) && measurement_valid && _range_sensor.isDataHealthy(); @@ -165,13 +166,17 @@ void Ekf::controlRangeHeightFusion() } else { if (starting_conditions_passing) { - if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL))) { + if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) + && (_params.rng_ctrl == static_cast(RngCtrl::CONDITIONAL)) + ) { // Range finder is used while hovering to stabilize the height estimate. Don't reset but use it as height reference. ECL_INFO("starting conditional %s height fusion", HGT_SRC_NAME); _height_sensor_ref = HeightSensor::RANGE; bias_est.setBias(_state.pos(2) + measurement); - } else if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) && (_params.rng_ctrl != static_cast(RngCtrl::CONDITIONAL))) { + } else if ((_params.height_sensor_ref == static_cast(HeightSensor::RANGE)) + && (_params.rng_ctrl != static_cast(RngCtrl::CONDITIONAL)) + ) { // Range finder is the primary height source, the ground is now the datum used // to compute the local vertical position ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME); @@ -203,6 +208,7 @@ void Ekf::controlRangeHeightFusion() bool Ekf::isConditionalRangeAidSuitable() { #if defined(CONFIG_EKF2_TERRAIN) + if (_control_status.flags.in_air && _range_sensor.isHealthy() && isTerrainEstimateValid()) { @@ -236,6 +242,7 @@ bool Ekf::isConditionalRangeAidSuitable() return is_in_range && is_hagl_stable && is_below_max_speed; } + #endif // CONFIG_EKF2_TERRAIN return false; @@ -250,7 +257,6 @@ void Ekf::stopRngHgtFusion() } _rng_hgt_b_est.setFusionInactive(); - resetEstimatorAidStatus(_aid_src_rng_hgt); _control_status.flags.rng_hgt = false; } diff --git a/src/modules/ekf2/EKF/sideslip_fusion.cpp b/src/modules/ekf2/EKF/sideslip_fusion.cpp index e806d13bfc..e6f035356f 100644 --- a/src/modules/ekf2/EKF/sideslip_fusion.cpp +++ b/src/modules/ekf2/EKF/sideslip_fusion.cpp @@ -76,26 +76,22 @@ void Ekf::controlBetaFusion(const imuSample &imu_delayed) } } -void Ekf::updateSideslip(estimator_aid_source1d_s &sideslip) const +void Ekf::updateSideslip(estimator_aid_source1d_s &aid_src) const { - // reset flags - resetEstimatorAidStatus(sideslip); + float observation = 0.f; + const float R = math::max(sq(_params.beta_noise), sq(0.01f)); // observation noise variance - const float R = sq(_params.beta_noise); // observation noise variance - - float innov = 0.f; - float innov_var = 0.f; + float innov; + float innov_var; sym::ComputeSideslipInnovAndInnovVar(_state.vector(), P, R, FLT_EPSILON, &innov, &innov_var); - sideslip.observation = 0.f; - sideslip.observation_variance = R; - sideslip.innovation = innov; - sideslip.innovation_variance = innov_var; - - sideslip.timestamp_sample = _time_delayed_us; - - const float innov_gate = fmaxf(_params.beta_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(sideslip, innov_gate); + updateEstimatorAidStatus(aid_src, + _time_delayed_us, // sample timestamp + observation, // observation + R, // observation variance + innov, // innovation + innov_var, // innovation variance + math::max(_params.beta_innov_gate, 1.f)); // gate sigma } void Ekf::fuseSideslip(estimator_aid_source1d_s &sideslip) diff --git a/src/modules/ekf2/EKF/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_estimator.cpp index 7e450f1253..740637b459 100644 --- a/src/modules/ekf2/EKF/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_estimator.cpp @@ -205,8 +205,6 @@ void Ekf::stopHaglRngFusion() ECL_INFO("stopping HAGL range fusion"); // reset flags - resetEstimatorAidStatus(_aid_src_terrain_range_finder); - _innov_check_fail_status.flags.reject_hagl = false; _hagl_sensor_status.flags.range_finder = false; @@ -233,18 +231,13 @@ void Ekf::updateHaglRng(estimator_aid_source1d_s &aid_src) const // perform an innovation consistency check and only fuse data if it passes const float innov_gate = fmaxf(_params.range_innov_gate, 1.0f); - - aid_src.timestamp_sample = _time_delayed_us; // TODO - - aid_src.observation = meas_hagl; - aid_src.observation_variance = obs_variance; - - aid_src.innovation = hagl_innov; - aid_src.innovation_variance = hagl_innov_var; - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - aid_src.fused = false; + updateEstimatorAidStatus(aid_src, + _time_delayed_us, // sample timestamp + meas_hagl, // observation + obs_variance, // observation variance + hagl_innov, // innovation + hagl_innov_var, // innovation variance + innov_gate); // gate sigma } void Ekf::fuseHaglRng(estimator_aid_source1d_s &aid_src) @@ -329,7 +322,6 @@ void Ekf::stopHaglFlowFusion() ECL_INFO("stopping HAGL flow fusion"); _hagl_sensor_status.flags.flow = false; - resetEstimatorAidStatus(_aid_src_terrain_optical_flow); } } @@ -345,31 +337,15 @@ void Ekf::resetHaglFlow() void Ekf::fuseFlowForTerrain(estimator_aid_source2d_s &flow) { - flow.fused = true; - - const float R_LOS = flow.observation_variance[0]; - - // calculate the height above the ground of the optical flow camera. Since earth frame is NED - // a positive offset in earth frame leads to a smaller height above the ground. - float range = predictFlowRange(); - - const float state = _terrain_vpos; // linearize both axes using the same state value - Vector2f innov_var; - float H; - sym::TerrEstComputeFlowXyInnovVarAndHx(state, _terrain_var, _state.quat_nominal, _state.vel, _state.pos(2), R_LOS, FLT_EPSILON, &innov_var, &H); - innov_var.copyTo(flow.innovation_variance); - - if ((flow.innovation_variance[0] < R_LOS) - || (flow.innovation_variance[1] < R_LOS)) { + if ((flow.innovation_variance[0] < flow.observation_variance[0]) + || (flow.innovation_variance[1] < flow.observation_variance[1]) + ) { // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); _terrain_var = 100.0f; return; } - // run the innovation consistency check and record result - setEstimatorAidStatusTestRatio(flow, math::max(_params.flow_innov_gate, 1.f)); - _innov_check_fail_status.flags.reject_optflow_X = (flow.test_ratio[0] > 1.f); _innov_check_fail_status.flags.reject_optflow_Y = (flow.test_ratio[1] > 1.f); @@ -378,6 +354,8 @@ void Ekf::fuseFlowForTerrain(estimator_aid_source2d_s &flow) return; } + float H = 0.f; + // fuse observation axes sequentially for (uint8_t index = 0; index <= 1; index++) { if (index == 0) { @@ -385,14 +363,14 @@ void Ekf::fuseFlowForTerrain(estimator_aid_source2d_s &flow) } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::TerrEstComputeFlowYInnovVarAndH(state, _terrain_var, _state.quat_nominal, _state.vel, _state.pos(2), R_LOS, FLT_EPSILON, &flow.innovation_variance[1], &H); + sym::TerrEstComputeFlowYInnovVarAndH(_terrain_vpos, _terrain_var, _state.quat_nominal, _state.vel, _state.pos(2), flow.observation_variance[1], FLT_EPSILON, &flow.innovation_variance[1], &H); // recalculate the innovation using the updated state const Vector2f vel_body = predictFlowVelBody(); - range = predictFlowRange(); + float range = predictFlowRange(); flow.innovation[1] = (-vel_body(0) / range) - flow.observation[1]; - if (flow.innovation_variance[1] < R_LOS) { + if (flow.innovation_variance[1] < flow.observation_variance[1]) { // we need to reinitialise the covariance matrix and abort this fusion step ECL_ERR("Opt flow error - covariance reset"); _terrain_var = 100.0f; diff --git a/src/modules/ekf2/EKF/vel_pos_fusion.cpp b/src/modules/ekf2/EKF/vel_pos_fusion.cpp index e615dc2d20..faf032054b 100644 --- a/src/modules/ekf2/EKF/vel_pos_fusion.cpp +++ b/src/modules/ekf2/EKF/vel_pos_fusion.cpp @@ -43,153 +43,139 @@ #include #include "ekf.h" -void Ekf::updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, - const float innov_gate, estimator_aid_source2d_s &aid_src) const +// TODO: void Ekf::updateYawAidSrcStatus(const uint64_t &time_us, const float &obs, const float &obs_var, +// const float innov_gate, estimator_aid_source1d_s &aid_src) const + +void Ekf::updateVelocityAidStatus(estimator_aid_source2d_s &aid_src, const uint64_t &time_us, + const Vector2f &observation, const Vector2f &observation_variance, float innovation_gate) const { - resetEstimatorAidStatus(aid_src); + Vector2f innovation = Vector2f(_state.vel.xy()) - observation; + Vector2f innovation_variance = Vector2f(getStateVariance()) + observation_variance; - for (int i = 0; i < 2; i++) { - aid_src.observation[i] = obs(i); - aid_src.innovation[i] = _state.vel(i) - aid_src.observation[i]; - - aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i)); - const int state_index = State::vel.idx + i; - aid_src.innovation_variance[i] = P(state_index, state_index) + aid_src.observation_variance[i]; - } - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - aid_src.timestamp_sample = time_us; + updateEstimatorAidStatus(aid_src, time_us, + observation, observation_variance, + innovation, innovation_variance, + innovation_gate); } -void Ekf::updateVelocityAidSrcStatus(const uint64_t &time_us, const Vector3f &obs, const Vector3f &obs_var, - const float innov_gate, estimator_aid_source3d_s &aid_src) const +void Ekf::updateVelocityAidStatus(estimator_aid_source3d_s &aid_src, const uint64_t &time_us, + const Vector3f &observation, const Vector3f &observation_variance, float innovation_gate) const { - resetEstimatorAidStatus(aid_src); + Vector3f innovation = _state.vel - observation; + Vector3f innovation_variance = getStateVariance() + observation_variance; - for (int i = 0; i < 3; i++) { - aid_src.observation[i] = obs(i); - aid_src.innovation[i] = _state.vel(i) - aid_src.observation[i]; - - aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i)); - const int state_index = State::vel.idx + i; - aid_src.innovation_variance[i] = P(state_index, state_index) + aid_src.observation_variance[i]; - } - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); + updateEstimatorAidStatus(aid_src, time_us, + observation, observation_variance, + innovation, innovation_variance, + innovation_gate); // vz special case if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter if (_fault_status.flags.bad_acc_vertical && aid_src.innovation_rejected) { - const float innov_limit = innov_gate * sqrtf(aid_src.innovation_variance[2]); + const float innov_limit = innovation_gate * sqrtf(aid_src.innovation_variance[2]); aid_src.innovation[2] = math::constrain(aid_src.innovation[2], -innov_limit, innov_limit); aid_src.innovation_rejected = false; } - - aid_src.timestamp_sample = time_us; } -void Ekf::updateVerticalPositionAidSrcStatus(const uint64_t &time_us, const float obs, const float obs_var, - const float innov_gate, estimator_aid_source1d_s &aid_src) const +void Ekf::updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, + const float observation, const float observation_variance, const float innovation_gate) const { - resetEstimatorAidStatus(aid_src); + float innovation = _state.pos(2) - observation; + float innovation_variance = getStateVariance()(2) + observation_variance; - aid_src.observation = obs; - aid_src.innovation = _state.pos(2) - aid_src.observation; - - aid_src.observation_variance = math::max(sq(0.01f), obs_var); - aid_src.innovation_variance = P(State::pos.idx + 2, State::pos.idx + 2) + aid_src.observation_variance; - - setEstimatorAidStatusTestRatio(aid_src, innov_gate); + updateEstimatorAidStatus(aid_src, time_us, + observation, observation_variance, + innovation, innovation_variance, + innovation_gate); // z special case if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter if (_fault_status.flags.bad_acc_vertical && aid_src.innovation_rejected) { - const float innov_limit = innov_gate * sqrtf(aid_src.innovation_variance); + const float innov_limit = innovation_gate * sqrtf(aid_src.innovation_variance); aid_src.innovation = math::constrain(aid_src.innovation, -innov_limit, innov_limit); aid_src.innovation_rejected = false; } - - aid_src.timestamp_sample = time_us; } -void Ekf::updateHorizontalPositionAidSrcStatus(const uint64_t &time_us, const Vector2f &obs, const Vector2f &obs_var, - const float innov_gate, estimator_aid_source2d_s &aid_src) const +void Ekf::updateHorizontalPositionAidStatus(estimator_aid_source2d_s &aid_src, const uint64_t &time_us, + const Vector2f &observation, const Vector2f &observation_variance, const float innov_gate) const { - resetEstimatorAidStatus(aid_src); + Vector2f innovation = Vector2f(_state.pos) - observation; + Vector2f innovation_variance = Vector2f(getStateVariance()) + observation_variance; - for (int i = 0; i < 2; i++) { - aid_src.observation[i] = obs(i); - aid_src.innovation[i] = _state.pos(i) - aid_src.observation[i]; + updateEstimatorAidStatus(aid_src, time_us, + observation, observation_variance, + innovation, innovation_variance, + innov_gate); +} - aid_src.observation_variance[i] = math::max(sq(0.01f), obs_var(i)); - const int state_index = State::pos.idx + i; - aid_src.innovation_variance[i] = P(state_index, state_index) + aid_src.observation_variance[i]; +bool Ekf::fuseVelocity(estimator_aid_source2d_s &aid_src) +{ + // vx, vy + if (!aid_src.innovation_rejected + && fuseVelPosHeight(aid_src.innovation[0], aid_src.innovation_variance[0], State::vel.idx + 0) + && fuseVelPosHeight(aid_src.innovation[1], aid_src.innovation_variance[1], State::vel.idx + 1) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; + + } else { + aid_src.fused = false; } - setEstimatorAidStatusTestRatio(aid_src, innov_gate); - - aid_src.timestamp_sample = time_us; + return aid_src.fused; } -void Ekf::fuseVelocity(estimator_aid_source2d_s &aid_src) +bool Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src) { - if (!aid_src.innovation_rejected) { - // vx, vy - if (fuseVelPosHeight(aid_src.innovation[0], aid_src.innovation_variance[0], State::vel.idx) - && fuseVelPosHeight(aid_src.innovation[1], aid_src.innovation_variance[1], State::vel.idx + 1) - ) { - aid_src.fused = true; - aid_src.time_last_fuse = _time_delayed_us; + // vx, vy, vz + if (!aid_src.innovation_rejected + && fuseVelPosHeight(aid_src.innovation[0], aid_src.innovation_variance[0], State::vel.idx + 0) + && fuseVelPosHeight(aid_src.innovation[1], aid_src.innovation_variance[1], State::vel.idx + 1) + && fuseVelPosHeight(aid_src.innovation[2], aid_src.innovation_variance[2], State::vel.idx + 2) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; - } else { - aid_src.fused = false; - } + } else { + aid_src.fused = false; } + + return aid_src.fused; } -void Ekf::fuseVelocity(estimator_aid_source3d_s &aid_src) -{ - if (!aid_src.innovation_rejected) { - // vx, vy, vz - if (fuseVelPosHeight(aid_src.innovation[0], aid_src.innovation_variance[0], State::vel.idx) - && fuseVelPosHeight(aid_src.innovation[1], aid_src.innovation_variance[1], State::vel.idx + 1) - && fuseVelPosHeight(aid_src.innovation[2], aid_src.innovation_variance[2], State::vel.idx + 2) - ) { - aid_src.fused = true; - aid_src.time_last_fuse = _time_delayed_us; - - } else { - aid_src.fused = false; - } - } -} - -void Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src) +bool Ekf::fuseHorizontalPosition(estimator_aid_source2d_s &aid_src) { // x & y - if (!aid_src.innovation_rejected) { - if (fuseVelPosHeight(aid_src.innovation[0], aid_src.innovation_variance[0], State::pos.idx) - && fuseVelPosHeight(aid_src.innovation[1], aid_src.innovation_variance[1], State::pos.idx + 1) - ) { - aid_src.fused = true; - aid_src.time_last_fuse = _time_delayed_us; + if (!aid_src.innovation_rejected + && fuseVelPosHeight(aid_src.innovation[0], aid_src.innovation_variance[0], State::pos.idx + 0) + && fuseVelPosHeight(aid_src.innovation[1], aid_src.innovation_variance[1], State::pos.idx + 1) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; - } else { - aid_src.fused = false; - } + } else { + aid_src.fused = false; } + + return aid_src.fused; } -void Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) +bool Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) { // z - if (!aid_src.innovation_rejected) { - if (fuseVelPosHeight(aid_src.innovation, aid_src.innovation_variance, State::pos.idx + 2)) { - aid_src.fused = true; - aid_src.time_last_fuse = _time_delayed_us; - } + if (!aid_src.innovation_rejected + && fuseVelPosHeight(aid_src.innovation, aid_src.innovation_variance, State::pos.idx + 2) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; + + } else { + aid_src.fused = false; } + + return aid_src.fused; } // Helper function that fuses a single velocity or position measurement diff --git a/src/modules/ekf2/EKF/yaw_fusion.cpp b/src/modules/ekf2/EKF/yaw_fusion.cpp index ddab6ee634..0f5cec8f7d 100644 --- a/src/modules/ekf2/EKF/yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/yaw_fusion.cpp @@ -38,23 +38,8 @@ #include -// update quaternion states and covariances using the yaw innovation and yaw observation variance -bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status) -{ - VectorState H_YAW; - computeYawInnovVarAndH(aid_src_status.observation_variance, aid_src_status.innovation_variance, H_YAW); - - return fuseYaw(aid_src_status, H_YAW); -} - bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW) { - // define the innovation gate size - float gate_sigma = math::max(_params.heading_innov_gate, 1.f); - - // innovation test ratio - setEstimatorAidStatusTestRatio(aid_src_status, gate_sigma); - // check if the innovation variance calculation is badly conditioned if (aid_src_status.innovation_variance >= aid_src_status.observation_variance) { // the innovation variance contribution from the state covariances is not negative, no fault @@ -84,7 +69,7 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H Kfusion(row) *= heading_innov_var_inv; } - // set the magnetometer unhealthy if the test fails + // set the heading unhealthy if the test fails if (aid_src_status.innovation_rejected) { _innov_check_fail_status.flags.reject_yaw = true; @@ -92,13 +77,14 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H // we allow to use it when on the ground because the large innovation could be caused // by interference or a large initial gyro bias if (!_control_status.flags.in_air - && isTimedOut(_time_last_in_air, (uint64_t)5e6) - && isTimedOut(aid_src_status.time_last_fuse, (uint64_t)1e6) - ) { + && isTimedOut(_time_last_in_air, (uint64_t)5e6) + && isTimedOut(aid_src_status.time_last_fuse, (uint64_t)1e6) + ) { // constrain the innovation to the maximum set by the gate // we need to delay this forced fusion to avoid starting it // immediately after touchdown, when the drone is still armed - float gate_limit = sqrtf((sq(gate_sigma) * aid_src_status.innovation_variance)); + const float gate_sigma = math::max(_params.heading_innov_gate, 1.f); + const float gate_limit = sqrtf((sq(gate_sigma) * aid_src_status.innovation_variance)); aid_src_status.innovation = math::constrain(aid_src_status.innovation, -gate_limit, gate_limit); // also reset the yaw gyro variance to converge faster and avoid @@ -123,13 +109,10 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H _fault_status.flags.bad_hdg = false; return true; - - } else { - _fault_status.flags.bad_hdg = true; } // otherwise - aid_src_status.fused = false; + _fault_status.flags.bad_hdg = true; return false; } 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 b79d6d2adb..d32efd6523 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -66,326 +66,326 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6390000,0.7,0.0014,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-3.6e-05,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 6490000,0.7,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-8.5e-05,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 6590000,0.7,0.0014,-0.014,0.71,0.0017,0.0057,-0.099,0.0034,0.0013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,9.5e-05,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6690000,0.7,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0036,0.0019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00022,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6790000,0.7,0.0014,-0.014,0.71,0.0008,0.0068,-0.11,0.0037,0.0026,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,8.4e-06,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6890000,0.7,0.0014,-0.014,0.71,-0.0012,0.0073,-0.12,0.0037,0.0033,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-4.3e-05,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6990000,0.71,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0035,0.0041,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00034,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7090000,0.71,0.0015,-0.014,0.71,-0.0018,0.0079,-0.13,0.0033,0.0049,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0007,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7190000,0.71,0.0015,-0.014,0.71,-0.0035,0.0081,-0.15,0.0031,0.0057,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00049,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7290000,0.71,0.0015,-0.014,0.71,-0.005,0.0083,-0.15,0.0026,0.0065,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0012,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0015,0.018,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7390000,0.71,0.0015,-0.014,0.71,-0.0051,0.0098,-0.16,0.0021,0.0073,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0013,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7490000,0.71,0.0016,-0.014,0.71,-0.0067,0.01,-0.16,0.0015,0.0083,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0021,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7590000,0.71,0.0016,-0.014,0.71,-0.0086,0.012,-0.17,0.00072,0.0093,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.003,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.51,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7690000,0.71,0.0017,-0.014,0.71,-0.01,0.012,-0.16,-0.00027,0.01,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.005,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7790000,0.71,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0014,0.011,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.007,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7890000,0.71,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0027,0.013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0096,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.65,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -7990000,0.71,0.0018,-0.014,0.71,-0.016,0.016,-0.16,-0.0043,0.014,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -8090000,0.71,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.006,0.016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8190000,0.71,0.0017,-0.014,0.71,-0.021,0.019,-0.18,-0.008,0.018,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.013,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8290000,0.71,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.017,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -8390000,0.71,0.0018,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.021,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.002,0.018,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0 -8490000,0.71,0.0018,-0.014,0.71,-0.026,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.025,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8590000,0.71,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.029,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8690000,0.71,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.026,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.035,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0 -8790000,0.71,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.041,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0 -8890000,0.71,0.0019,-0.014,0.71,-0.036,0.028,-0.15,-0.027,0.03,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.045,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0 -8990000,0.71,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.051,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0 -9090000,0.71,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.053,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0 -9190000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.036,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.057,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0 -9290000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.041,0.037,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.061,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0 -9390000,0.71,0.002,-0.014,0.71,-0.044,0.033,-0.14,-0.045,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.065,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,1.7,1.7,0.093,5.8,5.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0 -9490000,0.71,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.047,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.068,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0025,0.018,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0 -9590000,0.71,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.052,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.072,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0 -9690000,0.71,0.002,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.077,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0 -9790000,0.71,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.047,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.082,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0 -9890000,0.71,0.002,-0.014,0.71,-0.049,0.038,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.085,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0 -9990000,0.71,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.05,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.089,0.37,0.0037,0.026,0,0,0,0,0,0.0028,0.0028,0.018,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0 -10090000,0.71,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.064,0.049,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.091,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0 -10190000,0.71,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.053,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0028,0.0028,0.018,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10290000,0.71,0.0021,-0.014,0.71,-0.052,0.041,-0.084,-0.075,0.057,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.098,0.37,0.0037,0.026,0,0,0,0,0,0.0029,0.0029,0.018,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10390000,0.71,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,4.8e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.003,0.003,0.018,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0 -10490000,0.71,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.0031,0.0031,0.018,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10590000,0.71,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3e-05,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0031,0.0031,0.018,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10690000,0.71,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0032,0.0032,0.018,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10790000,0.71,0.0023,-0.014,0.71,0.0052,-0.003,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0031,0.0031,0.018,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10890000,0.71,0.0022,-0.014,0.71,0.0039,-0.0017,0.02,0.0031,-0.00092,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0032,0.0032,0.018,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10990000,0.71,0.0022,-0.014,0.71,0.0067,0.0034,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0029,0.0029,0.018,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11090000,0.71,0.0022,-0.014,0.71,0.0055,0.0059,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.003,0.003,0.018,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11190000,0.71,0.002,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11290000,0.71,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11390000,0.71,0.0022,-0.014,0.71,0.0053,0.0092,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.0005,0.00088,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11490000,0.71,0.0022,-0.014,0.71,0.0028,0.012,0.0025,0.0059,-0.00089,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.00051,0.00089,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11590000,0.71,0.0021,-0.014,0.71,-0.0016,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,4.6e-05,-8.6e-05,0.00077,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11690000,0.71,0.002,-0.014,0.71,-0.0044,0.013,-0.0079,0.0042,-0.00026,-3.7e+02,-0.0014,-0.0056,4.6e-05,-7.7e-05,0.00076,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11790000,0.71,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,4.6e-05,3.2e-05,0.00057,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11890000,0.71,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00076,0.0019,-3.7e+02,-0.0014,-0.0056,4.6e-05,2.6e-05,0.00057,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +6690000,0.7,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0035,0.0019,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00022,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6790000,0.7,0.0014,-0.014,0.71,0.00079,0.0067,-0.11,0.0037,0.0026,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,8.4e-06,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6890000,0.7,0.0014,-0.014,0.71,-0.0012,0.0073,-0.12,0.0036,0.0033,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-4.3e-05,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6990000,0.7,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0035,0.0041,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00034,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7090000,0.7,0.0015,-0.014,0.71,-0.0019,0.0079,-0.13,0.0033,0.0049,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0007,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7190000,0.7,0.0015,-0.014,0.71,-0.0036,0.008,-0.15,0.0031,0.0057,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.00049,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7290000,0.7,0.0015,-0.014,0.71,-0.005,0.0083,-0.15,0.0026,0.0064,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0012,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0015,0.018,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,6.3e-06,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7390000,0.7,0.0015,-0.014,0.71,-0.0052,0.0098,-0.16,0.0021,0.0073,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0013,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7490000,0.7,0.0016,-0.014,0.71,-0.0068,0.01,-0.16,0.0015,0.0083,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0021,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7590000,0.7,0.0016,-0.014,0.71,-0.0086,0.012,-0.17,0.00071,0.0093,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.003,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.51,0.51,0.14,1.1,1.1,0.12,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7690000,0.7,0.0017,-0.014,0.71,-0.01,0.012,-0.16,-0.00028,0.01,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.005,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7790000,0.7,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0014,0.011,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.007,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,6.3e-06,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7890000,0.7,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0028,0.013,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.0096,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.65,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +7990000,0.7,0.0018,-0.014,0.71,-0.016,0.016,-0.16,-0.0043,0.014,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,6.3e-06,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +8090000,0.7,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.006,0.016,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.011,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8190000,0.7,0.0018,-0.014,0.71,-0.021,0.019,-0.18,-0.008,0.017,-3.7e+02,-0.0015,-0.0057,5e-05,0,0,-0.013,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,6.3e-06,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8290000,0.7,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.017,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +8390000,0.7,0.0019,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.021,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.002,0.018,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,6.3e-06,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +8490000,0.7,0.0018,-0.014,0.71,-0.026,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.025,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8590000,0.7,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.029,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8690000,0.7,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.026,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.035,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,6.3e-06,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +8790000,0.7,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.041,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,6.3e-06,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +8890000,0.7,0.0019,-0.014,0.71,-0.036,0.028,-0.15,-0.027,0.029,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.045,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +8990000,0.7,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.051,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,6.3e-06,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +9090000,0.7,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.053,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +9190000,0.7,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.036,-3.7e+02,-0.0015,-0.0056,5e-05,0,0,-0.057,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.027,0,0,0,0,0,0,0,0 +9290000,0.7,0.002,-0.014,0.71,-0.043,0.03,-0.14,-0.041,0.037,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.061,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +9390000,0.7,0.002,-0.014,0.71,-0.044,0.033,-0.14,-0.045,0.039,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.065,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,1.7,1.7,0.093,5.8,5.8,0.086,0.00013,0.00013,6.3e-06,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +9490000,0.7,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.047,0.04,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.068,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0025,0.018,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.023,0,0,0,0,0,0,0,0 +9590000,0.7,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.052,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.072,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,6.3e-06,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +9690000,0.7,0.002,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.077,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +9790000,0.7,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.082,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +9890000,0.7,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.085,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.018,0,0,0,0,0,0,0,0 +9990000,0.7,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.05,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.089,0.37,0.0037,0.026,0,0,0,0,0,0.0028,0.0028,0.018,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,6.3e-06,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +10090000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.091,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +10190000,0.7,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.053,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0028,0.0028,0.018,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10290000,0.7,0.0021,-0.014,0.71,-0.053,0.04,-0.084,-0.076,0.056,-3.7e+02,-0.0015,-0.0056,4.8e-05,0,0,-0.098,0.37,0.0037,0.026,0,0,0,0,0,0.0029,0.0029,0.018,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,6.3e-06,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10390000,0.7,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,4.8e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.003,0.003,0.018,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +10490000,0.7,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.8e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.0031,0.0031,0.018,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10590000,0.7,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0031,0.0031,0.018,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10690000,0.7,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,-0.00027,3.2e-05,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0032,0.0032,0.018,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10790000,0.7,0.0023,-0.014,0.71,0.0052,-0.003,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0031,0.0031,0.018,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10890000,0.7,0.0022,-0.014,0.71,0.0039,-0.0017,0.02,0.0031,-0.00092,-3.7e+02,-0.0014,-0.0056,4.8e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0032,0.0032,0.018,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,6.3e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10990000,0.7,0.0022,-0.014,0.71,0.0067,0.0034,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0029,0.0029,0.018,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11090000,0.7,0.0022,-0.014,0.71,0.0055,0.0059,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,4.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.003,0.003,0.018,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,6.3e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11190000,0.7,0.0021,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00092,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11290000,0.7,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,4.4e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0027,0.0027,0.018,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11390000,0.7,0.0022,-0.014,0.71,0.0053,0.0092,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.0005,0.00089,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11490000,0.7,0.0022,-0.014,0.71,0.0028,0.012,0.0025,0.0059,-0.00089,-3.7e+02,-0.0013,-0.0056,4.6e-05,-0.00051,0.00089,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,6.3e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11590000,0.7,0.0021,-0.014,0.71,-0.0016,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,4.6e-05,-8.7e-05,0.00077,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11690000,0.71,0.002,-0.014,0.71,-0.0044,0.013,-0.0079,0.0042,-0.00027,-3.7e+02,-0.0014,-0.0056,4.6e-05,-7.7e-05,0.00076,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11790000,0.71,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,4.6e-05,3e-05,0.00057,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11890000,0.71,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00076,0.0019,-3.7e+02,-0.0014,-0.0056,4.6e-05,2.5e-05,0.00057,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.3e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 11990000,0.71,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.0003,0.0023,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00017,0.00059,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12090000,0.71,0.0021,-0.014,0.71,-0.015,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00018,0.00057,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12190000,0.71,0.0017,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00044,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0012,0.0012,0.018,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12290000,0.71,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00055,0.0033,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00041,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0013,0.0012,0.018,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12090000,0.71,0.0021,-0.014,0.71,-0.015,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,4.6e-05,0.00018,0.00058,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12190000,0.71,0.0018,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00043,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0012,0.0012,0.018,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12290000,0.71,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00055,0.0033,-3.7e+02,-0.0013,-0.0057,4.3e-05,0.00041,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0013,0.0013,0.018,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 12390000,0.71,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0011,0.0011,0.018,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 12490000,0.71,0.0014,-0.014,0.71,-0.0063,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,4.1e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0011,0.0011,0.018,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,6.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12590000,0.71,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00071,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.001,0.001,0.018,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 +12590000,0.71,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.0007,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.001,0.001,0.018,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 12690000,0.71,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.00073,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.001,0.001,0.018,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,6.3e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0 -12790000,0.71,0.0015,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00077,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00094,0.00094,0.018,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 +12790000,0.71,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.00077,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00094,0.00094,0.018,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 12890000,0.71,0.0015,-0.013,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.0007,0.0011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00097,0.00097,0.018,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,6.3e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0 12990000,0.71,0.0012,-0.014,0.71,-0.0084,0.0066,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,4e-05,0.00068,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00089,0.00089,0.018,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 13090000,0.71,0.0012,-0.014,0.71,-0.0091,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0012,-0.0059,4e-05,0.00065,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00092,0.00092,0.018,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,6.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 -13190000,0.71,0.00091,-0.014,0.71,1.9e-05,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00051,0.0014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00086,0.00086,0.018,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 -13290000,0.71,0.00092,-0.014,0.71,-0.00022,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00037,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 -13390000,0.71,0.00077,-0.014,0.71,0.0006,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0002,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 -13490000,0.71,0.0008,-0.014,0.71,0.00011,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.00012,0.0016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 -13590000,0.71,0.00074,-0.014,0.71,0.00036,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.006,3.7e-05,9e-05,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 -13690000,0.71,0.00072,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.006,3.7e-05,0.00012,0.0014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 -13790000,0.71,0.0006,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,3.6e-05,-0.0001,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.0008,0.018,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 -13890000,0.71,0.00057,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,3.6e-05,-7.1e-05,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00083,0.00083,0.018,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 -13990000,0.71,0.0005,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 -14090000,0.71,0.00049,-0.014,0.71,0.0025,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00033,0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00082,0.00082,0.018,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 -14190000,0.71,0.00038,-0.014,0.71,0.0058,0.00062,-0.033,0.0068,-0.0017,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00031,0.00088,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 -14290000,0.71,0.00039,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00038,0.00094,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.00081,0.018,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 -14390000,0.71,0.00031,-0.014,0.71,0.0084,0.0023,-0.034,0.0088,-0.0013,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00039,0.00069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00078,0.00078,0.018,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 -14490000,0.71,0.0003,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.0011,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00034,0.00064,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 -14590000,0.71,0.00028,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00071,0.001,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 -14690000,0.71,0.00024,-0.013,0.71,0.0063,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00082,0.0011,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 -14790000,0.71,0.00027,-0.013,0.71,0.0031,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.018,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 -14890000,0.71,0.00026,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 -14990000,0.71,0.00026,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.018,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 -15090000,0.71,0.00018,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00078,0.00078,0.019,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 -15190000,0.71,0.0002,-0.013,0.71,0.0032,-0.0008,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00075,0.00075,0.019,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 -15290000,0.71,0.00016,-0.013,0.71,0.0038,-0.00064,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.019,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 -15390000,0.71,0.00017,-0.013,0.71,0.003,-0.0003,-0.024,0.00057,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00074,0.00074,0.019,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.3e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 -15490000,0.71,0.00019,-0.013,0.71,0.0043,-0.00068,-0.024,0.00095,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.019,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.3e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 -15590000,0.71,0.0002,-0.013,0.71,0.0024,-0.00067,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 -15690000,0.71,0.00021,-0.013,0.71,0.0027,-0.00085,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00074,0.00074,0.019,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0 -15790000,0.71,0.00017,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00095,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00071,0.00071,0.019,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0 -15890000,0.71,0.00012,-0.013,0.71,0.0041,-0.003,-0.024,-0.00056,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0 -15990000,0.71,6.3e-05,-0.013,0.71,0.004,-0.0039,-0.019,-0.00063,-0.0039,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 -16090000,0.71,6.5e-05,-0.013,0.71,0.0057,-0.0041,-0.016,-0.00016,-0.0043,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00071,0.00072,0.019,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 -16190000,0.71,9.1e-05,-0.013,0.71,0.0057,-0.0033,-0.014,-0.00037,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 -16290000,0.71,0.00011,-0.013,0.71,0.0073,-0.0041,-0.016,0.00029,-0.0038,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 -16390000,0.71,0.0001,-0.013,0.71,0.0062,-0.0044,-0.015,-4.2e-05,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00067,0.00067,0.019,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 -16490000,0.71,0.00012,-0.013,0.71,0.0054,-0.0039,-0.018,0.00051,-0.0035,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 -16590000,0.71,0.00038,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-8.7e-05,-3.7e+02,-0.0013,-0.006,4e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00065,0.019,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0 -16690000,0.71,0.00036,-0.013,0.71,0.002,-0.00074,-0.015,-0.0022,-0.00018,-3.7e+02,-0.0013,-0.006,4e-05,-0.0011,0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00067,0.00067,0.019,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 -16790000,0.71,0.00051,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0005,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00064,0.00064,0.019,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 -16890000,0.71,0.00053,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00054,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00065,0.019,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 -16990000,0.71,0.00047,-0.013,0.71,-0.0016,0.00032,-0.01,-0.0052,0.00085,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00095,0.0051,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00062,0.00062,0.019,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 -17090000,0.71,0.00043,-0.013,0.71,-0.0008,0.0013,-0.01,-0.0053,0.0009,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00063,0.00063,0.019,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 -17190000,0.71,0.00042,-0.013,0.71,-0.00034,0.0013,-0.011,-0.0056,-0.00054,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0006,0.0006,0.019,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 -17290000,0.71,0.0004,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00038,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00061,0.00061,0.019,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 -17390000,0.71,0.00036,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0046,-0.0016,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00059,0.00059,0.019,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 -17490000,0.71,0.00036,-0.013,0.71,0.0029,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0006,0.0006,0.019,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 -17590000,0.71,0.00027,-0.013,0.71,0.0042,-0.00013,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00057,0.00057,0.019,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 -17690000,0.71,0.00024,-0.013,0.71,0.0051,0.00058,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00058,0.00058,0.019,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 -17790000,0.71,0.00015,-0.013,0.71,0.0076,0.0003,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00055,0.019,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 -17890000,0.71,0.00016,-0.013,0.71,0.0092,-0.00046,0.00069,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 -17990000,0.71,0.00011,-0.013,0.71,0.011,-0.0022,0.0019,-0.00052,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00054,0.00054,0.019,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0 -18090000,0.71,0.00011,-0.013,0.71,0.012,-0.0024,0.0043,0.0006,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00055,0.00055,0.019,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 -18190000,0.71,8e-05,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00053,0.019,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 -18290000,0.71,2.1e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0018,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 -18390000,0.71,3.9e-05,-0.013,0.71,0.013,-0.0002,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 -18490000,0.71,5.4e-05,-0.012,0.71,0.014,0.00021,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00052,0.00052,0.019,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 -18590000,0.71,6.1e-05,-0.012,0.71,0.013,0.00045,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 -18690000,0.71,3e-05,-0.012,0.71,0.014,-0.00024,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.00051,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 -18790000,0.71,5.9e-05,-0.012,0.71,0.012,6.6e-05,0.0035,0.0037,-0.00091,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 -18890000,0.71,8.5e-05,-0.012,0.71,0.013,0.00056,0.0042,0.005,-0.00084,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0 -18990000,0.71,7.3e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0 -19090000,0.71,5.8e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.0005,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 -19190000,0.71,6.1e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00045,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 -19290000,0.71,8.3e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00026,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0 -19390000,0.71,9.6e-05,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0 -19490000,0.71,0.00012,-0.012,0.71,0.012,-0.00032,0.0088,0.0092,-0.00028,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0 -19590000,0.71,0.00017,-0.012,0.71,0.0096,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0 -19690000,0.71,0.00017,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00054,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0 -19790000,0.71,0.00024,-0.012,0.71,0.0077,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19890000,0.71,0.00019,-0.012,0.71,0.0064,-0.0047,0.011,0.0075,-0.0009,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00044,0.019,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19990000,0.71,0.00018,-0.012,0.71,0.004,-0.0054,0.014,0.0061,-0.00075,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20090000,0.71,0.00018,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20190000,0.71,0.00028,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20290000,0.71,0.00024,-0.012,0.71,0.00031,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20390000,0.71,0.00026,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20490000,0.71,0.00032,-0.012,0.71,-0.0026,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20590000,0.71,0.00034,-0.012,0.71,-0.0023,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20790000,0.71,0.0004,-0.012,0.71,-0.0034,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.0004,0.019,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.0004,0.019,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -21090000,0.71,0.00039,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -21190000,0.71,0.00043,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.71,0.00047,-0.012,0.71,-0.004,-0.018,0.016,0.0034,-0.0055,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.0004,0.019,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.71,0.00051,-0.012,0.71,-0.0048,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00035,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21590000,0.71,0.00055,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-4.5e-06,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00038,0.019,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21690000,0.71,0.00056,-0.012,0.71,-0.0057,-0.017,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,4.4e-05,-5.7e-06,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,7.2e-05,-0.00078,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00052,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21890000,0.71,0.00058,-0.012,0.71,-0.0063,-0.012,0.016,-0.00057,-0.0019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21990000,0.71,0.00063,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00096,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22090000,0.71,0.00064,-0.012,0.71,-0.0072,-0.0083,0.015,-0.0022,0.0006,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22190000,0.71,0.00061,-0.012,0.71,-0.007,-0.0074,0.015,-0.0018,0.00056,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22290000,0.71,0.00065,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.00022,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00037,0.02,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22390000,0.71,0.00063,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.0002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22490000,0.71,0.00063,-0.012,0.71,-0.0096,-0.0075,0.018,-0.0031,-0.00098,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22590000,0.71,0.00062,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00011,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22690000,0.71,0.00065,-0.012,0.71,-0.011,-0.0068,0.018,-0.0044,-0.00058,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0056,0.019,-0.0055,-0.00047,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00036,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22990000,0.71,0.00063,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00089,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00036,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23190000,0.71,0.00066,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23290000,0.71,0.0006,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23390000,0.71,0.00069,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0077,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0025,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23790000,0.71,0.005,0.00066,0.71,-0.089,-0.028,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.002,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.037,-0.2,-0.03,-0.0051,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23990000,0.7,0.00098,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0083,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +13190000,0.71,0.00093,-0.014,0.71,1.1e-05,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.0005,0.0014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00086,0.00086,0.018,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13290000,0.71,0.00093,-0.014,0.71,-0.00023,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00037,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,6.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13390000,0.71,0.00079,-0.014,0.71,0.00059,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0002,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 +13490000,0.71,0.00081,-0.014,0.71,9.9e-05,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.00011,0.0016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,6.3e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 +13590000,0.71,0.00076,-0.014,0.71,0.00035,0.0061,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.006,3.7e-05,8.7e-05,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 +13690000,0.71,0.00073,-0.014,0.71,0.001,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.006,3.7e-05,0.00011,0.0014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,6.3e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 +13790000,0.71,0.00062,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,3.6e-05,-0.0001,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.0008,0.018,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 +13890000,0.71,0.00058,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,3.6e-05,-7.4e-05,0.0013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00083,0.00083,0.018,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 +13990000,0.71,0.00052,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 +14090000,0.71,0.0005,-0.014,0.71,0.0025,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00033,0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00082,0.00082,0.018,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,6.3e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 +14190000,0.71,0.0004,-0.014,0.71,0.0058,0.00063,-0.033,0.0068,-0.0017,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00032,0.00089,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 +14290000,0.71,0.00041,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00039,0.00094,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.00081,0.018,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,6.3e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 +14390000,0.71,0.00032,-0.014,0.71,0.0084,0.0023,-0.034,0.0088,-0.0013,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.0004,0.00069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00078,0.00078,0.018,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 +14490000,0.71,0.00031,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.0011,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00034,0.00064,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,6.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 +14590000,0.71,0.0003,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00071,0.0011,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 +14690000,0.71,0.00026,-0.013,0.71,0.0063,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00082,0.0011,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,6.3e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 +14790000,0.71,0.00028,-0.013,0.71,0.0031,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.018,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 +14890000,0.71,0.00028,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,6.3e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 +14990000,0.71,0.00027,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.018,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 +15090000,0.71,0.0002,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00078,0.00078,0.019,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.3e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 +15190000,0.71,0.00021,-0.013,0.71,0.0032,-0.00079,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00075,0.00075,0.019,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 +15290000,0.71,0.00018,-0.013,0.71,0.0038,-0.00063,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.019,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.3e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 +15390000,0.71,0.00018,-0.013,0.71,0.003,-0.00029,-0.024,0.00057,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00074,0.00074,0.019,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.3e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 +15490000,0.71,0.0002,-0.013,0.71,0.0043,-0.00067,-0.024,0.00095,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.019,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.3e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 +15590000,0.71,0.00022,-0.013,0.71,0.0024,-0.00066,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 +15690000,0.71,0.00022,-0.013,0.71,0.0027,-0.00084,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00074,0.00074,0.019,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.3e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0 +15790000,0.71,0.00018,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00095,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00071,0.00071,0.019,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0 +15890000,0.71,0.00013,-0.013,0.71,0.0041,-0.003,-0.024,-0.00056,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0 +15990000,0.71,7.6e-05,-0.013,0.71,0.004,-0.0039,-0.019,-0.00063,-0.0039,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 +16090000,0.71,7.8e-05,-0.013,0.71,0.0057,-0.0041,-0.016,-0.00016,-0.0043,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00071,0.00072,0.019,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.3e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 +16190000,0.71,0.0001,-0.013,0.71,0.0057,-0.0033,-0.014,-0.00037,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 +16290000,0.71,0.00012,-0.013,0.71,0.0073,-0.0041,-0.016,0.00029,-0.0038,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6.3e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 +16390000,0.71,0.00011,-0.013,0.71,0.0062,-0.0044,-0.015,-4.3e-05,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00067,0.00067,0.019,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 +16490000,0.71,0.00013,-0.013,0.71,0.0054,-0.0039,-0.018,0.00051,-0.0035,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,6.3e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 +16590000,0.71,0.00039,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-8.4e-05,-3.7e+02,-0.0013,-0.006,4e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00065,0.019,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0 +16690000,0.71,0.00038,-0.013,0.71,0.002,-0.00073,-0.015,-0.0022,-0.00018,-3.7e+02,-0.0013,-0.006,4e-05,-0.0011,0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00067,0.00067,0.019,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,6.3e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 +16790000,0.71,0.00052,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0005,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00064,0.00064,0.019,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 +16890000,0.71,0.00054,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00054,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00065,0.019,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,6.3e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 +16990000,0.71,0.00048,-0.013,0.71,-0.0016,0.00033,-0.01,-0.0052,0.00085,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00095,0.0051,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00062,0.00062,0.019,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17090000,0.71,0.00045,-0.013,0.71,-0.0008,0.0013,-0.01,-0.0053,0.0009,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00094,0.0051,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00063,0.00063,0.019,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,6.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17190000,0.71,0.00043,-0.013,0.71,-0.00035,0.0013,-0.011,-0.0056,-0.00054,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0006,0.0006,0.019,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 +17290000,0.71,0.00041,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00037,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00061,0.00061,0.019,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,6.3e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 +17390000,0.71,0.00037,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0046,-0.0016,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00059,0.00059,0.019,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17490000,0.71,0.00037,-0.013,0.71,0.0029,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0006,0.0006,0.019,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,6.3e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17590000,0.71,0.00028,-0.013,0.71,0.0042,-0.00011,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00057,0.00057,0.019,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17690000,0.71,0.00025,-0.013,0.71,0.0051,0.0006,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00058,0.00058,0.019,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,6.3e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17790000,0.71,0.00017,-0.013,0.71,0.0076,0.00032,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00055,0.019,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17890000,0.71,0.00018,-0.013,0.71,0.0092,-0.00044,0.00069,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,6.3e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17990000,0.71,0.00012,-0.013,0.71,0.011,-0.0022,0.0019,-0.00053,-0.0019,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00054,0.00054,0.019,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0 +18090000,0.71,0.00012,-0.013,0.71,0.012,-0.0024,0.0043,0.0006,-0.0021,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00055,0.00055,0.019,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,6.3e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 +18190000,0.71,9.2e-05,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00053,0.019,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 +18290000,0.71,3.3e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0027,-0.0018,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00053,0.019,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,6.3e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 +18390000,0.71,5e-05,-0.013,0.71,0.013,-0.00018,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.00051,0.019,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 +18490000,0.71,6.6e-05,-0.012,0.71,0.014,0.00023,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00052,0.00052,0.019,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,6.3e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 +18590000,0.71,7.3e-05,-0.012,0.71,0.013,0.00047,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0005,0.0005,0.019,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 +18690000,0.71,4.1e-05,-0.012,0.71,0.014,-0.00022,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.00051,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,6.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 +18790000,0.71,7.1e-05,-0.012,0.71,0.012,8.2e-05,0.0035,0.0037,-0.0009,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00049,0.019,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 +18890000,0.71,9.7e-05,-0.012,0.71,0.013,0.00058,0.0042,0.005,-0.00084,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00049,0.019,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,6.3e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0 +18990000,0.71,8.5e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00048,0.019,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0 +19090000,0.71,6.9e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.00049,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00048,0.019,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,6.3e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 +19190000,0.71,7.3e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0086,-0.00044,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00047,0.00047,0.019,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 +19290000,0.71,9.5e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00026,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00047,0.00047,0.019,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,6.3e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0 +19390000,0.71,0.00011,-0.012,0.71,0.013,0.0004,0.012,0.008,-0.00027,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0 +19490000,0.71,0.00013,-0.012,0.71,0.012,-0.00031,0.0088,0.0092,-0.00027,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0 +19590000,0.71,0.00018,-0.012,0.71,0.0096,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0 +19690000,0.71,0.00018,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00054,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.3e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0 +19790000,0.71,0.00025,-0.012,0.71,0.0077,-0.0044,0.01,0.0068,-0.00043,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00044,0.019,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0075,-0.0009,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00044,0.019,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19990000,0.71,0.00019,-0.012,0.71,0.004,-0.0054,0.014,0.0061,-0.00075,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.025,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20090000,0.71,0.00019,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20290000,0.71,0.00025,-0.012,0.71,0.00033,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20390000,0.71,0.00027,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20490000,0.71,0.00033,-0.012,0.71,-0.0026,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20590000,0.71,0.00035,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20690000,0.71,0.00038,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,2e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20790000,0.71,0.00041,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.0004,0.019,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20890000,0.71,0.0004,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20990000,0.71,0.0004,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.0004,0.019,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21090000,0.71,0.0004,-0.012,0.71,-0.0041,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.0004,0.019,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21190000,0.71,0.00044,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00074,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.71,0.00048,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0055,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.0004,0.019,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.71,0.00053,-0.012,0.71,-0.0047,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.71,0.00053,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,4.4e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.71,0.00056,-0.012,0.71,-0.0058,-0.016,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-7.2e-06,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00038,0.019,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21690000,0.71,0.00057,-0.012,0.71,-0.0057,-0.017,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,4.4e-05,-8.4e-06,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.02,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.71,0.00059,-0.012,0.71,-0.0063,-0.011,0.015,8.3e-05,-0.00078,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00052,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.71,0.00059,-0.012,0.71,-0.0063,-0.012,0.016,-0.00055,-0.0019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.71,0.00064,-0.012,0.71,-0.0068,-0.0092,0.016,-0.0015,0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22090000,0.71,0.00065,-0.012,0.71,-0.0071,-0.0083,0.015,-0.0021,0.00059,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.02,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22190000,0.71,0.00063,-0.012,0.71,-0.007,-0.0074,0.015,-0.0018,0.00055,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22290000,0.71,0.00066,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0025,-0.00023,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.001,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00037,0.02,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22390000,0.71,0.00064,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.00021,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22490000,0.71,0.00065,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0031,-0.00099,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0011,0.007,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22590000,0.71,0.00063,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.0001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22690000,0.71,0.00067,-0.012,0.71,-0.01,-0.0068,0.018,-0.0044,-0.00059,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22790000,0.71,0.00065,-0.012,0.71,-0.011,-0.0056,0.019,-0.0055,-0.00047,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00036,0.02,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22890000,0.71,0.00066,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.001,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22990000,0.71,0.00064,-0.012,0.71,-0.012,-0.0057,0.022,-0.0074,-0.0009,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23090000,0.71,0.0006,-0.012,0.71,-0.013,-0.0057,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00036,0.02,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23190000,0.71,0.00067,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23290000,0.71,0.00061,-0.012,0.71,-0.015,-0.0079,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0014,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23390000,0.71,0.0007,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.009,-0.012,-0.018,-0.0027,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23590000,0.71,0.0083,-0.0017,0.71,-0.034,-0.0077,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23690000,0.7,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0025,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00036,0.02,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23790000,0.7,0.005,0.00066,0.71,-0.089,-0.028,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.002,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23890000,0.7,0.0024,-0.0054,0.71,-0.11,-0.037,-0.2,-0.03,-0.0051,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23990000,0.7,0.00099,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0083,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 24090000,0.7,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.018,0.019,0.0078,0.045,0.045,0.035,6.8e-07,6.8e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 24190000,0.7,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0077,0.04,0.04,0.035,6.5e-07,6.4e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 24290000,0.7,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.019,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0024,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24390000,0.7,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24490000,0.7,0.0047,-0.0018,0.71,-0.14,-0.058,-0.51,-0.077,-0.036,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24390000,0.7,0.0039,-0.0059,0.71,-0.13,-0.053,-0.46,-0.064,-0.03,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24490000,0.7,0.0047,-0.0017,0.71,-0.14,-0.058,-0.51,-0.077,-0.036,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 24590000,0.7,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24690000,0.7,0.0052,0.0028,0.71,-0.18,-0.083,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24790000,0.7,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24690000,0.7,0.0052,0.0028,0.71,-0.18,-0.083,-0.64,-0.098,-0.053,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.002,0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24790000,0.7,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.064,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 24890000,0.7,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.074,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0024,0.0034,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24990000,0.7,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00034,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25090000,0.7,0.0088,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25190000,0.7,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25390000,0.7,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.00021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00035,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.00019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00036,0.02,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0029,-0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00035,0.02,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00037,0.02,0.017,0.02,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00039,0.019,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -25890000,0.7,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0037,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00039,0.019,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -25990000,0.7,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00037,0.019,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24990000,0.7,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.082,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00034,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25090000,0.7,0.0088,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.094,-3.7e+02,-0.0013,-0.0059,4.3e-05,0.0033,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25190000,0.7,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0029,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00034,0.02,0.018,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25390000,0.7,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.0002,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00035,0.02,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0032,-0.00018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00036,0.02,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00035,0.02,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.0029,-0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00037,0.02,0.017,0.02,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0038,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00039,0.019,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +25890000,0.7,0.017,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0038,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00039,0.019,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +25990000,0.7,0.016,0.025,0.71,-0.66,-0.34,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00037,0.019,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0034,-0.0054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00042,0.019,0.017,0.023,0.008,0.044,0.044,0.035,4.6e-07,4.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,4e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00046,0.018,0.016,0.022,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,4e-05,0.0045,-0.0093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00047,0.018,0.017,0.025,0.008,0.044,0.045,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26390000,0.7,0.023,0.043,0.71,-0.94,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00044,0.018,0.016,0.024,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,3.8e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00056,0.018,0.018,0.027,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00096,-0.0059,4.7e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00067,0.017,0.016,0.027,0.008,0.039,0.041,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00096,-0.0059,4.7e-05,0.0041,-0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.0007,0.017,0.018,0.032,0.008,0.043,0.046,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26790000,0.7,0.036,0.072,0.71,-1.4,-0.74,-1.3,-1,-0.86,-3.7e+02,-0.00092,-0.006,2.9e-05,0.0021,-0.017,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.0006,0.015,0.017,0.031,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26890000,0.7,0.044,0.094,0.71,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.006,2.9e-05,0.002,-0.017,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00081,0.015,0.019,0.037,0.0081,0.043,0.046,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26990000,0.7,0.051,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.006,3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00096,0.014,0.018,0.036,0.008,0.039,0.042,0.035,4.1e-07,4.3e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 -27090000,0.7,0.052,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.006,3e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.001,0.013,0.02,0.045,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0 -27190000,0.71,0.049,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00012,0.0028,-0.023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.0008,0.012,0.02,0.045,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0 -27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00012,0.0027,-0.023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00067,0.012,0.022,0.052,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 -27390000,0.72,0.037,0.077,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00071,-0.0059,0.0002,0.0036,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.0005,0.011,0.021,0.048,0.0081,0.053,0.059,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 -27490000,0.72,0.031,0.062,0.69,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00071,-0.0059,0.0002,0.0035,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00043,0.011,0.023,0.052,0.0082,0.058,0.067,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 -27590000,0.72,0.026,0.05,0.69,-2.5,-1.1,-1.2,-2.5,-1.6,-3.7e+02,-0.00072,-0.0059,0.00026,0.0024,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00036,0.0094,0.021,0.045,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 -27690000,0.72,0.026,0.048,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.00072,-0.0059,0.00026,0.0023,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00036,0.0094,0.023,0.046,0.0082,0.067,0.077,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 -27790000,0.72,0.026,0.05,0.69,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00071,-0.0059,0.0003,0.0016,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00035,0.0084,0.021,0.04,0.0082,0.069,0.078,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 -27890000,0.72,0.025,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.00071,-0.0059,0.0003,0.0015,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00035,0.0085,0.023,0.042,0.0083,0.075,0.087,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 -27990000,0.72,0.025,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00074,-0.0059,0.00033,0.00042,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0077,0.022,0.037,0.0083,0.078,0.088,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 -28090000,0.72,0.031,0.057,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00074,-0.0059,0.00033,0.00028,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00036,0.0077,0.023,0.038,0.0084,0.085,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 -28190000,0.72,0.036,0.07,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00076,-0.0059,0.00035,-0.00051,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00039,0.0071,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 -28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.089,-4.5,-2.4,-3.7e+02,-0.00076,-0.0059,0.00035,-0.00069,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0072,0.022,0.035,0.0086,0.094,0.11,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 -28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00076,-0.0059,0.00035,-0.001,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00031,0.0073,0.023,0.036,0.0087,0.1,0.12,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 -28490000,0.73,0.0015,0.0046,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00076,-0.0059,0.00035,-0.0013,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00032,0.0073,0.024,0.036,0.0088,0.11,0.13,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 -28590000,0.73,-0.00034,0.0012,0.69,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00075,-0.0059,0.00035,-0.0016,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00032,0.0073,0.025,0.035,0.0089,0.12,0.14,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 -28690000,0.73,-0.0011,0.00028,0.69,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00075,-0.0059,0.00035,-0.0021,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0073,0.026,0.035,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 -28790000,0.73,-0.0015,9.3e-05,0.68,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.00081,-0.006,0.00038,-0.0039,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.007,0.025,0.03,0.0089,0.13,0.15,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 -28890000,0.73,-0.0015,0.00032,0.69,-2.5,-1.2,0.96,-6.1,-3.1,-3.7e+02,-0.00081,-0.006,0.00038,-0.0043,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.007,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 -28990000,0.73,-0.0014,0.00081,0.68,-2.5,-1.1,0.95,-6.5,-3.2,-3.7e+02,-0.00089,-0.006,0.0004,-0.0051,-0.03,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 -29090000,0.73,-0.0013,0.0012,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00089,-0.006,0.0004,-0.0056,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.009,0.15,0.17,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 -29190000,0.73,-0.0011,0.0017,0.68,-2.4,-1.1,0.93,-7,-3.4,-3.7e+02,-0.00093,-0.006,0.00041,-0.0066,-0.031,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.15,0.17,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 -29290000,0.73,-0.00074,0.0025,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00093,-0.006,0.00041,-0.0072,-0.03,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 -29390000,0.73,-0.00021,0.004,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.00099,-0.006,0.00041,-0.0081,-0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 -29490000,0.73,0.00033,0.0051,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.00099,-0.006,0.00041,-0.0085,-0.032,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.17,0.19,0.037,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 -29590000,0.73,0.00073,0.0063,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.001,-0.006,0.00039,-0.011,-0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.024,0.025,0.009,0.17,0.19,0.036,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 -29690000,0.73,0.001,0.0069,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.001,-0.006,0.00039,-0.011,-0.031,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.18,0.2,0.036,3.7e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,4e-05,0.0046,-0.0093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00046,0.018,0.016,0.022,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,4e-05,0.0046,-0.0092,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00047,0.018,0.017,0.025,0.008,0.044,0.045,0.035,4.5e-07,4.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.7,0.023,0.043,0.71,-0.94,-0.5,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,3.9e-05,0.0034,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00044,0.018,0.016,0.024,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.7,0.031,0.059,0.71,-1,-0.54,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,3.9e-05,0.0033,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00056,0.018,0.018,0.027,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00096,-0.0059,4.9e-05,0.0042,-0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00067,0.017,0.016,0.027,0.008,0.039,0.041,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00096,-0.0059,4.9e-05,0.0042,-0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.0007,0.017,0.018,0.032,0.008,0.043,0.046,0.035,4.3e-07,4.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.7,0.036,0.072,0.71,-1.4,-0.74,-1.3,-1,-0.86,-3.7e+02,-0.00092,-0.006,3.1e-05,0.0021,-0.017,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.0006,0.015,0.017,0.031,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.7,0.044,0.094,0.71,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.006,3.1e-05,0.0021,-0.017,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00081,0.015,0.019,0.037,0.0081,0.043,0.046,0.035,4.2e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.7,0.051,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.006,3.2e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00096,0.014,0.018,0.036,0.008,0.039,0.042,0.035,4.1e-07,4.3e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 +27090000,0.7,0.051,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.006,3.2e-05,0.0029,-0.022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.001,0.013,0.02,0.045,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,6.2e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0 +27190000,0.71,0.049,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00013,0.0028,-0.023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.0008,0.012,0.02,0.045,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0 +27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00013,0.0028,-0.023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00067,0.012,0.022,0.052,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,6.1e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 +27390000,0.72,0.037,0.077,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00071,-0.0059,0.0002,0.0037,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.0005,0.011,0.021,0.048,0.0081,0.053,0.059,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 +27490000,0.72,0.031,0.062,0.7,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00071,-0.0059,0.0002,0.0036,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00043,0.011,0.023,0.052,0.0082,0.058,0.067,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 +27590000,0.72,0.026,0.05,0.69,-2.5,-1.1,-1.2,-2.5,-1.6,-3.7e+02,-0.00072,-0.0059,0.00027,0.0024,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00036,0.0094,0.021,0.045,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 +27690000,0.72,0.026,0.048,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.00072,-0.0059,0.00027,0.0024,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00036,0.0094,0.023,0.046,0.0082,0.067,0.077,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 +27790000,0.72,0.026,0.05,0.69,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00071,-0.0059,0.00031,0.0017,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00035,0.0084,0.021,0.04,0.0082,0.069,0.078,0.035,3.9e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 +27890000,0.72,0.025,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.00071,-0.0059,0.00031,0.0015,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00035,0.0085,0.023,0.042,0.0083,0.076,0.087,0.035,4e-07,4.4e-07,6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 +27990000,0.72,0.025,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00074,-0.0059,0.00034,0.00045,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0077,0.022,0.037,0.0083,0.078,0.088,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 +28090000,0.72,0.031,0.057,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00074,-0.0059,0.00034,0.00032,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00036,0.0077,0.023,0.038,0.0084,0.085,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 +28190000,0.72,0.036,0.07,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00076,-0.0059,0.00036,-0.00048,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00039,0.0071,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 +28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.089,-4.5,-2.4,-3.7e+02,-0.00076,-0.0059,0.00036,-0.00066,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0072,0.022,0.035,0.0086,0.094,0.11,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 +28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00076,-0.0059,0.00036,-0.00096,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00031,0.0073,0.023,0.036,0.0087,0.1,0.12,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 +28490000,0.73,0.0015,0.0046,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00076,-0.0059,0.00036,-0.0012,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00032,0.0073,0.024,0.036,0.0088,0.11,0.13,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 +28590000,0.73,-0.00032,0.0012,0.69,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00075,-0.0059,0.00036,-0.0016,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00032,0.0073,0.025,0.035,0.0089,0.12,0.14,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 +28690000,0.73,-0.0011,0.00027,0.69,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00075,-0.0059,0.00036,-0.002,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0073,0.026,0.035,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 +28790000,0.73,-0.0015,8.7e-05,0.69,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.00081,-0.006,0.00039,-0.0039,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.007,0.025,0.03,0.0089,0.13,0.15,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 +28890000,0.73,-0.0015,0.00031,0.69,-2.5,-1.2,0.96,-6.1,-3.1,-3.7e+02,-0.00081,-0.006,0.00039,-0.0043,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.007,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 +28990000,0.73,-0.0014,0.00081,0.68,-2.5,-1.1,0.95,-6.5,-3.2,-3.7e+02,-0.00089,-0.006,0.00041,-0.0051,-0.03,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 +29090000,0.73,-0.0013,0.0012,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00089,-0.006,0.00041,-0.0056,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.009,0.15,0.17,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 +29190000,0.73,-0.0011,0.0017,0.68,-2.4,-1.1,0.93,-7,-3.4,-3.7e+02,-0.00093,-0.006,0.00041,-0.0067,-0.031,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.15,0.17,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29290000,0.73,-0.00073,0.0025,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00093,-0.006,0.00041,-0.0073,-0.03,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.4e-07,5.9e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29390000,0.73,-0.00019,0.004,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.00099,-0.006,0.00041,-0.0081,-0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 +29490000,0.73,0.00034,0.0051,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.00099,-0.006,0.00041,-0.0086,-0.032,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.17,0.19,0.037,3.7e-07,4.4e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29590000,0.73,0.00075,0.0063,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.001,-0.006,0.0004,-0.011,-0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.024,0.025,0.009,0.17,0.19,0.036,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29690000,0.73,0.001,0.0069,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.001,-0.006,0.0004,-0.011,-0.031,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.026,0.0091,0.18,0.2,0.036,3.7e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 29790000,0.73,0.0013,0.0075,0.68,-2.2,-1.1,0.94,-8.6,-4,-3.7e+02,-0.0011,-0.006,0.00038,-0.012,-0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.025,0.0091,0.18,0.2,0.037,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 29890000,0.73,0.0014,0.0077,0.68,-2.1,-1.1,0.92,-8.8,-4.1,-3.7e+02,-0.0011,-0.006,0.00038,-0.013,-0.031,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.19,0.21,0.037,3.6e-07,4.3e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 -29990000,0.73,0.0016,0.0079,0.68,-2.1,-1.1,0.91,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.00035,-0.015,-0.03,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.19,0.21,0.036,3.5e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 -30090000,0.73,0.0015,0.0078,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.00035,-0.016,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30190000,0.73,0.0016,0.0077,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0011,-0.0059,0.00032,-0.017,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30290000,0.73,0.0015,0.0075,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0011,-0.0059,0.00032,-0.018,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +29990000,0.73,0.0016,0.0079,0.68,-2.1,-1.1,0.91,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.00036,-0.015,-0.03,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.19,0.21,0.036,3.5e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +30090000,0.73,0.0016,0.0078,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.00036,-0.016,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.027,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30190000,0.73,0.0017,0.0077,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0011,-0.0059,0.00033,-0.017,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.026,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,5.9e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30290000,0.73,0.0015,0.0075,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0011,-0.0059,0.00033,-0.018,-0.029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.028,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 30390000,0.73,0.0016,0.0074,0.68,-2,-1,0.85,-9.9,-4.6,-3.7e+02,-0.0012,-0.0059,0.0003,-0.019,-0.028,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.025,0.027,0.009,0.21,0.23,0.036,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 30490000,0.73,0.0014,0.0071,0.68,-2,-1,0.83,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.0003,-0.019,-0.027,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0069,0.026,0.029,0.0091,0.22,0.24,0.037,3.4e-07,4e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 30590000,0.73,0.0014,0.0068,0.68,-1.9,-1,0.79,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00027,-0.02,-0.026,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.025,0.028,0.009,0.22,0.24,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30690000,0.73,0.0012,0.0065,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00027,-0.021,-0.025,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.03,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30790000,0.73,0.0013,0.0062,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00023,-0.021,-0.025,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0067,0.025,0.029,0.009,0.23,0.25,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30890000,0.73,0.0011,0.0058,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00023,-0.022,-0.024,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.031,0.009,0.24,0.26,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30990000,0.73,0.0011,0.0053,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.023,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0066,0.025,0.03,0.0089,0.24,0.26,0.036,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -31090000,0.73,0.00088,0.0048,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.00019,-0.023,-0.021,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0067,0.026,0.032,0.009,0.25,0.27,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31190000,0.73,0.0009,0.0045,0.68,-1.8,-0.99,0.73,-12,-5.4,-3.7e+02,-0.0013,-0.0059,0.00016,-0.024,-0.019,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0065,0.025,0.03,0.0088,0.25,0.27,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31290000,0.73,0.00065,0.004,0.68,-1.8,-0.99,0.74,-12,-5.5,-3.7e+02,-0.0013,-0.0059,0.00016,-0.025,-0.017,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0065,0.026,0.032,0.0089,0.26,0.28,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31390000,0.73,0.00059,0.0035,0.68,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0059,0.00013,-0.026,-0.016,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0064,0.025,0.031,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31490000,0.73,0.00036,0.0029,0.68,-1.7,-0.98,0.73,-12,-5.7,-3.7e+02,-0.0013,-0.0059,0.00013,-0.026,-0.014,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0064,0.026,0.033,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31590000,0.73,0.00041,0.0025,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,9.2e-05,-0.027,-0.013,-0.099,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0063,0.025,0.031,0.0087,0.26,0.29,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31690000,0.73,0.00013,0.0019,0.69,-1.7,-0.95,0.73,-13,-5.8,-3.7e+02,-0.0013,-0.0058,9.1e-05,-0.028,-0.011,-0.099,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0063,0.027,0.033,0.0088,0.28,0.3,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31790000,0.73,3.3e-05,0.0012,0.69,-1.6,-0.94,0.72,-13,-5.9,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.028,-0.0095,-0.098,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0061,0.025,0.031,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31890000,0.73,-0.00024,0.00054,0.69,-1.6,-0.93,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,5.4e-05,-0.029,-0.0082,-0.097,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0061,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31990000,0.73,-0.00027,4.8e-05,0.69,-1.6,-0.91,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,2e-05,-0.029,-0.0062,-0.097,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0059,0.025,0.032,0.0086,0.28,0.31,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -32090000,0.73,-0.00058,-0.00066,0.69,-1.5,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,2e-05,-0.03,-0.0047,-0.096,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.006,0.027,0.034,0.0087,0.29,0.32,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -32190000,0.72,-0.00071,-0.0015,0.69,-1.5,-0.89,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0058,-1.2e-05,-0.031,-0.0025,-0.096,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0058,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32290000,0.72,-0.00096,-0.0022,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-1.3e-05,-0.031,-0.00086,-0.095,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0058,0.026,0.034,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32390000,0.72,-0.0011,-0.0029,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.032,7.9e-05,-0.095,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00034,0.0056,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32490000,0.72,-0.0012,-0.0031,0.69,-1.4,-0.86,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-3.5e-05,-0.032,0.0012,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0056,0.026,0.034,0.0085,0.31,0.34,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32590000,0.72,-0.0011,-0.0033,0.69,-1.4,-0.85,0.71,-14,-6.6,-3.7e+02,-0.0014,-0.0058,-5.7e-05,-0.032,0.0021,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0055,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32690000,0.72,-0.0012,-0.0034,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-5.7e-05,-0.032,0.0026,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00034,0.0055,0.026,0.034,0.0085,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32790000,0.72,-0.001,-0.0034,0.69,-1.3,-0.82,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0036,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0053,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32890000,0.72,-0.00095,-0.0033,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0058,-7.8e-05,-0.033,0.0048,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0053,0.026,0.034,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32990000,0.72,-0.00074,-0.0033,0.69,-1.3,-0.8,0.7,-15,-6.9,-3.7e+02,-0.0014,-0.0058,-9.7e-05,-0.033,0.0061,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0051,0.025,0.032,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33090000,0.72,-0.00077,-0.0033,0.69,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0058,-9.7e-05,-0.034,0.0067,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0052,0.026,0.034,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33190000,0.72,0.0027,-0.0025,0.7,-1.2,-0.78,0.64,-15,-7,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.0075,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.005,0.025,0.031,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33290000,0.67,0.015,-0.0017,0.75,-1.2,-0.77,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.0078,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.005,0.026,0.033,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33390000,0.56,0.013,-0.0019,0.83,-1.2,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.0088,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0049,0.025,0.03,0.0083,0.35,0.38,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33490000,0.43,0.0064,0.00072,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00034,0.0049,0.026,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33590000,0.27,0.00058,-0.0017,0.96,-1.2,-0.74,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0048,0.026,0.031,0.0078,0.35,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33690000,0.1,-0.0027,-0.0046,0.99,-1.1,-0.74,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00014,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.0048,0.028,0.035,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33790000,-0.067,-0.0042,-0.0065,1,-1.1,-0.72,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00016,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.0003,0.0046,0.028,0.035,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33890000,-0.23,-0.0053,-0.0072,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00016,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.0003,0.0047,0.032,0.039,0.0072,0.38,0.41,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33990000,-0.38,-0.0035,-0.011,0.92,-0.97,-0.66,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.0003,0.0045,0.032,0.039,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34090000,-0.49,-0.0024,-0.013,0.87,-0.92,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.0003,0.0045,0.037,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34190000,-0.56,-0.0017,-0.011,0.83,-0.9,-0.57,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.0002,-0.037,0.011,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00029,0.00029,0.0044,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34290000,-0.6,-0.0026,-0.0086,0.8,-0.85,-0.52,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.0002,-0.037,0.011,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00029,0.0003,0.0044,0.043,0.05,0.0066,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34390000,-0.63,-0.0027,-0.0062,0.78,-0.84,-0.48,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.041,0.016,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00026,0.00028,0.0043,0.043,0.049,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34490000,-0.65,-0.0036,-0.004,0.76,-0.79,-0.44,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.041,0.016,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00026,0.00028,0.0043,0.05,0.056,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34590000,-0.65,-0.0029,-0.0031,0.76,-0.79,-0.42,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.05,0.025,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00024,0.00025,0.0043,0.048,0.053,0.0063,0.4,0.44,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34690000,-0.66,-0.0033,-0.0023,0.75,-0.73,-0.38,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.05,0.025,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00024,0.00025,0.0043,0.056,0.061,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34790000,-0.66,-0.0021,-0.0021,0.75,-0.74,-0.37,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.061,0.036,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00023,0.0042,0.052,0.057,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34890000,-0.67,-0.0022,-0.002,0.74,-0.69,-0.34,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00022,-0.061,0.036,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00023,0.0042,0.06,0.065,0.0062,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34990000,-0.67,-0.0085,-0.0048,0.74,0.33,0.25,-0.13,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.06,0.071,0.0068,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35090000,-0.67,-0.0085,-0.0048,0.74,0.46,0.27,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.065,0.078,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35190000,-0.67,-0.0085,-0.0048,0.74,0.48,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.071,0.083,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35290000,-0.67,-0.0086,-0.0049,0.74,0.5,0.33,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.076,0.089,0.0067,0.46,0.48,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35390000,-0.67,-0.0086,-0.0049,0.74,0.52,0.37,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.083,0.096,0.0066,0.47,0.5,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35490000,-0.67,-0.0087,-0.0049,0.74,0.55,0.4,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00022,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.089,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35590000,-0.67,-0.0056,-0.0051,0.74,0.43,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00016,0.00018,0.004,0.07,0.077,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35690000,-0.67,-0.0056,-0.0051,0.74,0.45,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.0002,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00016,0.00018,0.0041,0.076,0.083,0.0062,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35790000,-0.67,-0.0034,-0.0052,0.74,0.37,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.076,0.052,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00014,0.00015,0.004,0.063,0.067,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35890000,-0.67,-0.0034,-0.0052,0.74,0.38,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.076,0.052,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00014,0.00015,0.004,0.068,0.072,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35990000,-0.67,-0.0015,-0.0052,0.74,0.32,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.083,0.059,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00012,0.00014,0.0039,0.058,0.061,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36090000,-0.67,-0.0016,-0.0051,0.74,0.33,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.083,0.059,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00012,0.00014,0.0039,0.064,0.067,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36190000,-0.67,-0.00015,-0.0051,0.74,0.27,0.26,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.093,0.068,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00011,0.00012,0.0039,0.056,0.058,0.0055,0.5,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36290000,-0.67,-0.00027,-0.005,0.74,0.28,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.093,0.068,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00011,0.00012,0.0039,0.061,0.063,0.0056,0.52,0.54,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36390000,-0.67,0.00078,-0.0049,0.74,0.23,0.24,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.11,0.077,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.9e-05,0.00011,0.0039,0.054,0.056,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36490000,-0.67,0.00068,-0.0049,0.74,0.24,0.25,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.11,0.077,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.9e-05,0.00011,0.0039,0.06,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36590000,-0.67,0.0015,-0.0048,0.74,0.2,0.22,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.12,0.087,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.1e-05,0.00011,0.0039,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36690000,-0.67,0.0014,-0.0047,0.74,0.2,0.23,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.12,0.087,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.2e-05,0.00011,0.0039,0.059,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36790000,-0.67,0.002,-0.0046,0.74,0.17,0.2,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.13,0.096,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.5e-05,9.9e-05,0.004,0.052,0.054,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36890000,-0.67,0.0019,-0.0046,0.74,0.17,0.22,-0.16,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.13,0.096,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.6e-05,9.9e-05,0.004,0.058,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36990000,-0.67,0.0024,-0.0044,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.14,0.1,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.1e-05,9.4e-05,0.004,0.052,0.053,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37090000,-0.67,0.0023,-0.0044,0.74,0.14,0.2,-0.15,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.14,0.1,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.1e-05,9.4e-05,0.004,0.057,0.058,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37190000,-0.67,0.0027,-0.0042,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.16,0.11,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.8e-05,9e-05,0.004,0.051,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37290000,-0.67,0.0026,-0.0042,0.74,0.12,0.18,-0.14,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.16,0.11,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.8e-05,9.1e-05,0.004,0.056,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37390000,-0.67,0.0029,-0.004,0.74,0.094,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.17,0.12,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.5e-05,8.8e-05,0.004,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37490000,-0.67,0.0028,-0.004,0.74,0.092,0.16,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.17,0.12,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.6e-05,8.8e-05,0.004,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37590000,-0.67,0.003,-0.0039,0.74,0.073,0.13,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.18,0.12,-0.095,0.37,0.0037,0.026,0,0,0,0,0,7.4e-05,8.6e-05,0.0041,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37690000,-0.67,0.0029,-0.0039,0.74,0.071,0.14,-0.11,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.18,0.12,-0.095,0.37,0.0037,0.026,0,0,0,0,0,7.4e-05,8.6e-05,0.0041,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37790000,-0.67,0.003,-0.0038,0.74,0.056,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.19,0.13,-0.096,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.5e-05,0.0041,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37890000,-0.67,0.003,-0.0038,0.74,0.053,0.13,-0.094,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.19,0.13,-0.096,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.5e-05,0.0041,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37990000,-0.67,0.0031,-0.0038,0.74,0.039,0.11,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.19,0.13,-0.096,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.4e-05,0.0041,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38090000,-0.67,0.003,-0.0038,0.74,0.035,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.19,0.13,-0.097,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0041,0.051,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38190000,-0.67,0.0031,-0.0037,0.74,0.023,0.094,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.2,0.13,-0.097,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.3e-05,0.0041,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.016,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38290000,-0.67,0.003,-0.0036,0.74,0.019,0.096,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.2,0.13,-0.097,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.4e-05,0.0041,0.049,0.05,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.016,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38390000,-0.67,0.0031,-0.0035,0.74,0.011,0.083,-0.052,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.2,0.14,-0.098,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.3e-05,0.0041,0.044,0.045,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38490000,-0.67,0.003,-0.0035,0.74,0.0081,0.085,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0041,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38590000,-0.67,0.0031,-0.0034,0.74,0.0039,0.073,-0.038,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.21,0.14,-0.099,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.3e-05,0.0041,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38690000,-0.67,0.003,-0.0034,0.74,-0.00048,0.073,-0.031,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.21,0.14,-0.099,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0042,0.046,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38790000,-0.67,0.003,-0.0033,0.74,-0.0052,0.061,-0.023,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.21,0.14,-0.099,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0042,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38890000,-0.67,0.0028,-0.0034,0.74,-0.015,0.051,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.21,0.14,-0.1,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0042,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +30690000,0.73,0.0013,0.0065,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00027,-0.021,-0.025,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.03,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,5.9e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30790000,0.73,0.0013,0.0062,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00024,-0.021,-0.025,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0067,0.025,0.029,0.009,0.23,0.25,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30890000,0.73,0.0011,0.0057,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00024,-0.022,-0.024,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0068,0.026,0.031,0.009,0.24,0.26,0.037,3.3e-07,3.8e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30990000,0.73,0.0011,0.0052,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.0002,-0.023,-0.023,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0066,0.025,0.03,0.0089,0.24,0.26,0.036,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +31090000,0.73,0.00089,0.0048,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.0002,-0.023,-0.021,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0067,0.026,0.032,0.009,0.25,0.27,0.037,3.3e-07,3.7e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31190000,0.73,0.00091,0.0045,0.68,-1.8,-0.99,0.73,-12,-5.4,-3.7e+02,-0.0013,-0.0059,0.00017,-0.024,-0.019,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0065,0.025,0.03,0.0088,0.25,0.27,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31290000,0.73,0.00066,0.004,0.68,-1.8,-0.99,0.74,-12,-5.5,-3.7e+02,-0.0013,-0.0059,0.00017,-0.025,-0.017,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0065,0.026,0.032,0.0089,0.26,0.28,0.037,3.2e-07,3.6e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31390000,0.73,0.0006,0.0035,0.69,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0059,0.00014,-0.026,-0.016,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0064,0.025,0.031,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31490000,0.73,0.00037,0.0029,0.69,-1.7,-0.97,0.73,-12,-5.7,-3.7e+02,-0.0013,-0.0059,0.00014,-0.026,-0.014,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0064,0.026,0.033,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,5.8e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31590000,0.73,0.00042,0.0025,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,0.0001,-0.027,-0.013,-0.099,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0063,0.025,0.031,0.0087,0.26,0.29,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31690000,0.73,0.00014,0.0019,0.69,-1.7,-0.95,0.73,-13,-5.8,-3.7e+02,-0.0013,-0.0058,0.0001,-0.028,-0.011,-0.099,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0063,0.027,0.033,0.0088,0.28,0.3,0.037,3.1e-07,3.4e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31790000,0.73,4.2e-05,0.0012,0.69,-1.6,-0.94,0.72,-13,-5.9,-3.7e+02,-0.0014,-0.0058,6.3e-05,-0.028,-0.0095,-0.098,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0061,0.025,0.031,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31890000,0.73,-0.00023,0.00054,0.69,-1.6,-0.93,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,6.2e-05,-0.029,-0.0082,-0.098,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0061,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31990000,0.73,-0.00026,4.2e-05,0.69,-1.6,-0.91,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,2.9e-05,-0.029,-0.0062,-0.097,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0059,0.025,0.032,0.0086,0.28,0.31,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32090000,0.73,-0.00057,-0.00067,0.69,-1.5,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,2.8e-05,-0.03,-0.0046,-0.096,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.006,0.027,0.034,0.0087,0.29,0.32,0.037,3.1e-07,3.3e-07,5.7e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32190000,0.72,-0.0007,-0.0015,0.69,-1.5,-0.89,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0058,-3.6e-06,-0.031,-0.0025,-0.096,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0058,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32290000,0.72,-0.00095,-0.0022,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-3.8e-06,-0.031,-0.00086,-0.095,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0058,0.026,0.034,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,5.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32390000,0.72,-0.0011,-0.0029,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-2.6e-05,-0.032,8.4e-05,-0.095,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00034,0.0056,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32490000,0.72,-0.0012,-0.0031,0.69,-1.4,-0.86,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-2.6e-05,-0.032,0.0012,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00034,0.0056,0.026,0.034,0.0085,0.31,0.34,0.037,3e-07,3.1e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32590000,0.72,-0.0011,-0.0033,0.69,-1.4,-0.85,0.71,-14,-6.6,-3.7e+02,-0.0014,-0.0058,-4.8e-05,-0.032,0.0021,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0055,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32690000,0.72,-0.0012,-0.0034,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-4.8e-05,-0.032,0.0026,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00034,0.0055,0.026,0.034,0.0085,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32790000,0.72,-0.001,-0.0034,0.69,-1.3,-0.82,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0058,-6.8e-05,-0.033,0.0037,-0.094,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0053,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32890000,0.72,-0.00094,-0.0033,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0058,-6.9e-05,-0.033,0.0048,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0053,0.026,0.034,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32990000,0.72,-0.00073,-0.0033,0.69,-1.3,-0.8,0.7,-15,-6.9,-3.7e+02,-0.0014,-0.0058,-8.8e-05,-0.033,0.0061,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0051,0.025,0.032,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33090000,0.72,-0.00077,-0.0033,0.69,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0058,-8.8e-05,-0.034,0.0067,-0.093,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0052,0.026,0.034,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33190000,0.72,0.0027,-0.0025,0.7,-1.2,-0.78,0.64,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.00011,-0.034,0.0075,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.005,0.025,0.031,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33290000,0.67,0.015,-0.0017,0.75,-1.2,-0.76,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.00011,-0.034,0.0079,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.005,0.026,0.033,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,5.6e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33390000,0.56,0.013,-0.0019,0.83,-1.2,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00033,0.0049,0.025,0.03,0.0083,0.35,0.38,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33490000,0.43,0.0064,0.00072,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00012,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.00034,0.0049,0.026,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33590000,0.27,0.00058,-0.0017,0.96,-1.2,-0.74,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00031,0.00033,0.0048,0.026,0.031,0.0078,0.35,0.39,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33690000,0.1,-0.0027,-0.0047,0.99,-1.1,-0.74,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00013,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.0048,0.028,0.035,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33790000,-0.067,-0.0042,-0.0065,1,-1.1,-0.72,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00015,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.0003,0.0046,0.028,0.035,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33890000,-0.23,-0.0053,-0.0072,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00015,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.0003,0.0047,0.032,0.039,0.0072,0.38,0.41,0.036,2.7e-07,2.8e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33990000,-0.38,-0.0035,-0.011,0.92,-0.97,-0.66,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00018,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.0003,0.0045,0.032,0.039,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34090000,-0.49,-0.0024,-0.013,0.87,-0.92,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00018,-0.034,0.0089,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.0003,0.0045,0.037,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34190000,-0.56,-0.0017,-0.011,0.83,-0.9,-0.57,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.037,0.011,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00029,0.00029,0.0044,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34290000,-0.6,-0.0026,-0.0086,0.8,-0.85,-0.52,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00019,-0.037,0.011,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00029,0.0003,0.0044,0.043,0.05,0.0066,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34390000,-0.63,-0.0027,-0.0062,0.78,-0.84,-0.48,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00021,-0.041,0.016,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00026,0.00028,0.0043,0.043,0.049,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34490000,-0.65,-0.0036,-0.004,0.76,-0.79,-0.44,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00021,-0.041,0.016,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00026,0.00028,0.0043,0.05,0.056,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,5.5e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34590000,-0.66,-0.0029,-0.0031,0.76,-0.79,-0.42,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00021,-0.051,0.025,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00024,0.00025,0.0043,0.048,0.053,0.0063,0.4,0.44,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34690000,-0.66,-0.0033,-0.0023,0.75,-0.74,-0.38,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00021,-0.051,0.025,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00024,0.00025,0.0043,0.056,0.061,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34790000,-0.67,-0.0021,-0.0021,0.75,-0.74,-0.37,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00021,-0.061,0.036,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00023,0.0042,0.052,0.057,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34890000,-0.67,-0.0022,-0.002,0.74,-0.69,-0.34,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00021,-0.061,0.036,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00023,0.0042,0.06,0.065,0.0062,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34990000,-0.67,-0.0085,-0.0048,0.74,0.33,0.25,-0.13,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00021,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.06,0.071,0.0068,0.42,0.46,0.034,2.6e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35090000,-0.67,-0.0085,-0.0048,0.74,0.46,0.27,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00021,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.065,0.078,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35190000,-0.67,-0.0085,-0.0048,0.74,0.48,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00021,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.071,0.083,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35290000,-0.67,-0.0086,-0.0049,0.74,0.5,0.33,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00021,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.076,0.089,0.0067,0.46,0.48,0.033,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35390000,-0.67,-0.0086,-0.0049,0.74,0.52,0.37,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00021,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.083,0.096,0.0066,0.47,0.5,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35490000,-0.67,-0.0087,-0.0049,0.74,0.55,0.4,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00021,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00021,0.0042,0.089,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,5.5e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35590000,-0.67,-0.0056,-0.0051,0.74,0.43,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00016,0.00018,0.004,0.07,0.077,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35690000,-0.67,-0.0056,-0.0051,0.74,0.45,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0058,-0.00019,-0.074,0.05,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00016,0.00018,0.0041,0.076,0.083,0.0062,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35790000,-0.67,-0.0034,-0.0051,0.74,0.37,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.076,0.052,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00014,0.00015,0.004,0.063,0.067,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35890000,-0.67,-0.0034,-0.0052,0.74,0.38,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.076,0.052,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00014,0.00015,0.004,0.068,0.072,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35990000,-0.67,-0.0015,-0.0052,0.74,0.32,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.083,0.059,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00012,0.00014,0.0039,0.058,0.061,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36090000,-0.67,-0.0016,-0.0051,0.74,0.33,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.083,0.059,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00012,0.00014,0.0039,0.064,0.067,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36190000,-0.67,-0.00015,-0.0051,0.74,0.27,0.26,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.093,0.068,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00011,0.00012,0.0039,0.056,0.058,0.0055,0.5,0.53,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36290000,-0.67,-0.00027,-0.005,0.74,0.28,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.093,0.068,-0.092,0.37,0.0037,0.026,0,0,0,0,0,0.00011,0.00012,0.0039,0.061,0.063,0.0056,0.52,0.54,0.032,2.7e-07,2.8e-07,5.4e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36390000,-0.67,0.00078,-0.0049,0.74,0.23,0.24,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.11,0.077,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.9e-05,0.00011,0.0039,0.054,0.056,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36490000,-0.67,0.00069,-0.0049,0.74,0.24,0.25,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.11,0.077,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.9e-05,0.00011,0.0039,0.06,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,5.4e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36590000,-0.67,0.0015,-0.0048,0.74,0.2,0.22,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.12,0.087,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.1e-05,0.00011,0.0039,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36690000,-0.67,0.0014,-0.0047,0.74,0.2,0.23,-0.17,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.12,0.087,-0.092,0.37,0.0037,0.026,0,0,0,0,0,9.2e-05,0.00011,0.0039,0.059,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36790000,-0.67,0.002,-0.0046,0.74,0.17,0.2,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.13,0.096,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.5e-05,9.9e-05,0.004,0.052,0.054,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36890000,-0.67,0.0019,-0.0046,0.74,0.17,0.22,-0.16,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.13,0.096,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.6e-05,9.9e-05,0.004,0.058,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36990000,-0.67,0.0024,-0.0044,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.14,0.1,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.1e-05,9.4e-05,0.004,0.052,0.053,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37090000,-0.67,0.0023,-0.0043,0.74,0.14,0.2,-0.15,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00014,-0.14,0.1,-0.093,0.37,0.0037,0.026,0,0,0,0,0,8.1e-05,9.4e-05,0.004,0.057,0.058,0.0057,0.56,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.022,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37190000,-0.67,0.0027,-0.0042,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.16,0.11,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.8e-05,9e-05,0.004,0.051,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37290000,-0.67,0.0026,-0.0042,0.74,0.12,0.18,-0.14,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.16,0.11,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.8e-05,9.1e-05,0.004,0.056,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,5.4e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37390000,-0.67,0.0029,-0.004,0.74,0.094,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.17,0.12,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.5e-05,8.8e-05,0.004,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37490000,-0.67,0.0028,-0.004,0.74,0.092,0.16,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.17,0.12,-0.094,0.37,0.0037,0.026,0,0,0,0,0,7.6e-05,8.8e-05,0.004,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.02,0.019,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37590000,-0.67,0.003,-0.0039,0.74,0.073,0.13,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.18,0.12,-0.095,0.37,0.0037,0.026,0,0,0,0,0,7.4e-05,8.6e-05,0.0041,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37690000,-0.67,0.0029,-0.0039,0.74,0.071,0.14,-0.11,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.00015,-0.18,0.12,-0.095,0.37,0.0037,0.026,0,0,0,0,0,7.4e-05,8.6e-05,0.0041,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,5.4e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37790000,-0.67,0.003,-0.0038,0.74,0.056,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.5e-05,0.0041,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37890000,-0.67,0.003,-0.0038,0.74,0.053,0.13,-0.094,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.5e-05,0.0041,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,5.4e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37990000,-0.67,0.0031,-0.0038,0.74,0.039,0.11,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.096,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.4e-05,0.0041,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38090000,-0.67,0.003,-0.0038,0.74,0.035,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00016,-0.19,0.13,-0.097,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0041,0.051,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38190000,-0.67,0.0031,-0.0037,0.74,0.023,0.094,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.13,-0.097,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.3e-05,0.0041,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.016,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38290000,-0.67,0.003,-0.0036,0.74,0.019,0.096,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.13,-0.097,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.4e-05,0.0041,0.049,0.05,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.016,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38390000,-0.67,0.0031,-0.0035,0.74,0.011,0.083,-0.052,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.2,0.14,-0.098,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.3e-05,0.0041,0.044,0.045,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38490000,-0.67,0.003,-0.0035,0.74,0.0081,0.085,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00017,-0.21,0.14,-0.098,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0041,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38590000,-0.67,0.0031,-0.0034,0.74,0.0039,0.073,-0.038,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.026,0,0,0,0,0,7.2e-05,8.3e-05,0.0041,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38690000,-0.67,0.003,-0.0034,0.74,-0.00044,0.073,-0.031,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0042,0.046,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38790000,-0.67,0.003,-0.0033,0.74,-0.0052,0.061,-0.023,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0042,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38890000,-0.67,0.0028,-0.0034,0.74,-0.015,0.051,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00018,-0.21,0.14,-0.1,0.37,0.0037,0.026,0,0,0,0,0,7.3e-05,8.4e-05,0.0042,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,5.4e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index f4f09cb978..eb59f12fc8 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -65,57 +65,57 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6290000,0.98,-0.0065,-0.013,0.19,0.0083,0.018,-0.041,0.0055,0.0071,-0.053,-0.0019,-0.0056,4.4e-05,0,0,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 6390000,0.98,-0.0065,-0.013,0.19,0.011,0.02,-0.042,0.0064,0.009,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 6490000,0.98,-0.0064,-0.013,0.19,0.0084,0.019,-0.039,0.0073,0.011,-0.053,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,6.3e-06,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 -6590000,0.98,-0.0064,-0.013,0.19,0.0078,0.022,-0.042,0.0082,0.013,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,6.3e-06,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 -6690000,0.98,-0.0063,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 +6590000,0.98,-0.0064,-0.013,0.19,0.0077,0.022,-0.042,0.0082,0.013,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,6.3e-06,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 +6690000,0.98,-0.0062,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 6790000,0.98,-0.0063,-0.013,0.19,0.007,0.027,-0.042,0.0093,0.018,-0.058,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0014,0.0014,0.018,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,6.3e-06,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 6890000,0.98,-0.0061,-0.013,0.19,0.0066,0.028,-0.038,0.01,0.02,-0.055,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,6.3e-06,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 6990000,0.98,-0.006,-0.013,0.19,0.0066,0.029,-0.037,0.011,0.023,-0.055,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 -7090000,0.98,-0.0059,-0.013,0.19,0.0058,0.035,-0.037,0.011,0.027,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 -7190000,0.98,-0.0058,-0.013,0.19,0.0054,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,6.3e-06,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 -7290000,0.98,-0.0058,-0.013,0.19,0.0062,0.043,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,6.3e-06,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 -7390000,0.98,-0.0057,-0.013,0.19,0.0045,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,6.3e-06,0.04,0.04,0.002,0,0,0,0,0,0,0,0 -7490000,0.98,-0.0057,-0.013,0.19,0.0068,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,6.3e-06,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 -7590000,0.98,-0.0057,-0.013,0.19,0.0078,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.025,1.2,1.2,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 -7690000,0.98,-0.0057,-0.013,0.19,0.0075,0.058,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 -7790000,0.98,-0.0056,-0.013,0.19,0.0091,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,6.3e-06,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 -7890000,0.98,-0.0056,-0.013,0.19,0.0078,0.066,-0.025,0.016,0.065,-0.045,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,6.3e-06,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 -7990000,0.98,-0.0056,-0.013,0.19,0.0079,0.068,-0.021,0.017,0.07,-0.041,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8090000,0.98,-0.0054,-0.013,0.19,0.0095,0.074,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.91,0.91,0.022,2.1,2.1,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8190000,0.98,-0.0055,-0.013,0.19,0.01,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.99,0.99,0.021,2.4,2.4,0.058,0.00014,0.00014,6.3e-06,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 -8290000,0.98,-0.0055,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8390000,0.98,-0.0054,-0.013,0.19,0.01,0.088,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,4.3e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8490000,0.98,-0.0053,-0.013,0.19,0.0097,0.091,-0.017,0.021,0.11,-0.041,-0.0018,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8590000,0.98,-0.0053,-0.013,0.19,0.011,0.095,-0.012,0.022,0.12,-0.036,-0.0018,-0.0056,4.3e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8690000,0.98,-0.0053,-0.013,0.19,0.011,0.096,-0.014,0.022,0.12,-0.037,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.001,0,0,0,0,0,0,0,0 -8790000,0.98,-0.0053,-0.013,0.19,0.012,0.1,-0.013,0.023,0.13,-0.035,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 -8890000,0.98,-0.0053,-0.013,0.19,0.012,0.1,-0.0091,0.023,0.14,-0.029,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 -8990000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0083,0.024,0.15,-0.032,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 +7090000,0.98,-0.0059,-0.013,0.19,0.0057,0.035,-0.037,0.011,0.027,-0.056,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,6.3e-06,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 +7190000,0.98,-0.0058,-0.013,0.19,0.0053,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,6.3e-06,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 +7290000,0.98,-0.0058,-0.013,0.19,0.0061,0.043,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,6.3e-06,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 +7390000,0.98,-0.0057,-0.013,0.19,0.0044,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,6.3e-06,0.04,0.04,0.002,0,0,0,0,0,0,0,0 +7490000,0.98,-0.0056,-0.013,0.19,0.0067,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0016,0.0016,0.018,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,6.3e-06,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 +7590000,0.98,-0.0057,-0.013,0.19,0.0077,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.6,0.6,0.025,1.2,1.2,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 +7690000,0.98,-0.0057,-0.013,0.19,0.0074,0.058,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,6.3e-06,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 +7790000,0.98,-0.0056,-0.013,0.19,0.0089,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,6.3e-06,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 +7890000,0.98,-0.0056,-0.013,0.19,0.0076,0.065,-0.025,0.016,0.065,-0.045,-0.0019,-0.0056,4.4e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,6.3e-06,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 +7990000,0.98,-0.0055,-0.013,0.19,0.0078,0.068,-0.021,0.016,0.07,-0.041,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8090000,0.98,-0.0054,-0.013,0.19,0.0093,0.074,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.91,0.91,0.022,2.1,2.1,0.059,0.00014,0.00014,6.3e-06,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8190000,0.98,-0.0054,-0.013,0.19,0.01,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0019,0.0019,0.018,0.99,0.99,0.021,2.4,2.4,0.058,0.00014,0.00014,6.3e-06,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 +8290000,0.98,-0.0054,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8390000,0.98,-0.0054,-0.013,0.19,0.0099,0.088,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,4.3e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,6.3e-06,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8490000,0.98,-0.0053,-0.013,0.19,0.0095,0.091,-0.017,0.02,0.11,-0.041,-0.0018,-0.0056,4.3e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8590000,0.98,-0.0052,-0.013,0.19,0.011,0.095,-0.012,0.021,0.12,-0.036,-0.0018,-0.0056,4.3e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,6.3e-06,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8690000,0.98,-0.0053,-0.013,0.19,0.01,0.096,-0.014,0.022,0.12,-0.037,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.001,0,0,0,0,0,0,0,0 +8790000,0.98,-0.0052,-0.013,0.19,0.012,0.1,-0.013,0.023,0.13,-0.035,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,6.3e-06,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 +8890000,0.98,-0.0053,-0.013,0.19,0.011,0.1,-0.0091,0.023,0.14,-0.029,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 +8990000,0.98,-0.0052,-0.013,0.19,0.011,0.11,-0.0083,0.024,0.15,-0.032,-0.0018,-0.0056,4.2e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,6.3e-06,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 9090000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0093,0.024,0.15,-0.032,-0.0018,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.7,1.7,0.016,5.4,5.4,0.053,0.00013,0.00013,6.3e-06,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 -9190000,0.98,-0.0053,-0.013,0.19,0.014,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.8,1.8,0.016,6,6.1,0.052,0.00013,0.00013,6.3e-06,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 +9190000,0.98,-0.0053,-0.013,0.19,0.014,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.8,1.8,0.016,6,6,0.052,0.00013,0.00013,6.3e-06,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 9290000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0072,0.025,0.16,-0.03,-0.0018,-0.0056,4e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,6.3e-06,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 9390000,0.98,-0.0051,-0.013,0.19,0.016,0.12,-0.006,0.027,0.17,-0.03,-0.0018,-0.0056,4e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,6.3e-06,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 -9490000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0044,0.027,0.17,-0.027,-0.0017,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,6.3e-06,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 -9590000,0.98,-0.0052,-0.013,0.19,0.016,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 -9690000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0014,0.028,0.18,-0.027,-0.0017,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,2,2,0.014,8,8.1,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 +9490000,0.98,-0.0052,-0.013,0.19,0.015,0.11,-0.0044,0.026,0.17,-0.027,-0.0017,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,6.3e-06,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 +9590000,0.98,-0.0052,-0.013,0.19,0.015,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,3.9e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 +9690000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0014,0.027,0.18,-0.027,-0.0017,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,2,2,0.014,8,8.1,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 9790000,0.98,-0.0053,-0.013,0.19,0.016,0.12,-0.0027,0.029,0.19,-0.028,-0.0017,-0.0056,3.8e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,2.1,2.1,0.014,8.9,8.9,0.05,0.00012,0.00012,6.3e-06,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 9890000,0.98,-0.0054,-0.013,0.19,0.018,0.11,-0.0014,0.028,0.19,-0.029,-0.0016,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 -9990000,0.98,-0.0054,-0.013,0.19,0.02,0.12,-0.00072,0.03,0.2,-0.031,-0.0016,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0022,0.018,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 -10090000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.00048,0.029,0.19,-0.029,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 -10190000,0.98,-0.0054,-0.013,0.19,0.016,0.11,0.0014,0.03,0.2,-0.03,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 -10290000,0.98,-0.0055,-0.013,0.19,0.016,0.11,0.0003,0.032,0.21,-0.029,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 +9990000,0.98,-0.0054,-0.013,0.19,0.019,0.12,-0.00072,0.029,0.2,-0.031,-0.0016,-0.0056,3.7e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0022,0.018,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,6.3e-06,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 +10090000,0.98,-0.0054,-0.013,0.19,0.017,0.11,0.00048,0.028,0.19,-0.029,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0021,0.0021,0.018,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 +10190000,0.98,-0.0054,-0.013,0.19,0.015,0.11,0.0014,0.03,0.2,-0.03,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 +10290000,0.98,-0.0054,-0.013,0.19,0.016,0.11,0.0003,0.032,0.21,-0.029,-0.0016,-0.0057,3.6e-05,0,0,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 10390000,0.98,-0.0054,-0.013,0.19,0.0071,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,3.6e-05,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 10490000,0.98,-0.0053,-0.012,0.19,0.0085,0.0077,0.007,0.0015,0.00076,-0.023,-0.0016,-0.0057,3.6e-05,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,3.6e-05,0.00032,9.5e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10690000,0.98,-0.0052,-0.012,0.19,-5.3e-05,0.0068,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,3.6e-05,0.00032,1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10790000,0.98,-0.0054,-0.013,0.19,0.0018,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,3.4e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,3.6e-05,0.00032,8.8e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10690000,0.98,-0.0052,-0.012,0.19,-7.4e-05,0.0068,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,3.6e-05,0.00032,9.5e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10790000,0.98,-0.0054,-0.013,0.19,0.0017,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,3.4e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 10890000,0.98,-0.0053,-0.013,0.19,0.0019,0.0066,0.01,-0.00059,-0.0042,-0.018,-0.0016,-0.0057,3.4e-05,0.00053,0.00048,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0026,0.0026,0.018,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,6.3e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10990000,0.98,-0.0054,-0.013,0.19,0.0014,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,3.4e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11090000,0.98,-0.0055,-0.013,0.19,0.0024,0.017,0.02,-0.0003,-0.0016,-0.0074,-0.0015,-0.0057,3.4e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11190000,0.98,-0.0058,-0.013,0.19,0.0041,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,3.2e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +10990000,0.98,-0.0054,-0.013,0.19,0.0013,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,3.4e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0024,0.0024,0.018,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11090000,0.98,-0.0055,-0.013,0.19,0.0023,0.017,0.02,-0.0003,-0.0016,-0.0074,-0.0015,-0.0057,3.4e-05,0.00068,0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0025,0.0025,0.018,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,6.3e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11190000,0.98,-0.0058,-0.013,0.19,0.004,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,3.2e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0022,0.0022,0.018,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 11290000,0.98,-0.0058,-0.013,0.19,0.0043,0.018,0.026,0.0015,-1.6e-05,-0.00012,-0.0015,-0.0057,3.1e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0023,0.0023,0.018,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 11390000,0.98,-0.006,-0.013,0.19,0.0026,0.015,0.016,0.00089,-0.00087,-0.0086,-0.0014,-0.0058,2.9e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.0019,0.018,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 11490000,0.98,-0.0059,-0.013,0.19,0.0017,0.017,0.02,0.001,0.00073,-0.0025,-0.0014,-0.0058,2.9e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.002,0.002,0.018,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,6.3e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11590000,0.98,-0.0062,-0.012,0.19,0.0034,0.013,0.018,0.00085,-0.00036,-0.0036,-0.0013,-0.0058,2.7e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11590000,0.98,-0.0062,-0.012,0.19,0.0034,0.013,0.018,0.00084,-0.00036,-0.0036,-0.0013,-0.0058,2.7e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0017,0.0017,0.018,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 11690000,0.98,-0.0062,-0.012,0.19,0.0039,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,2.7e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0018,0.0018,0.018,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,6.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 11790000,0.98,-0.0066,-0.012,0.19,0.0025,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,2.3e-05,0.002,0.0036,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 11890000,0.98,-0.0067,-0.012,0.19,0.0052,0.012,0.017,0.001,-0.00069,-0.0013,-0.0012,-0.0059,2.3e-05,0.002,0.0036,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0015,0.0015,0.018,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 @@ -123,11 +123,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 12090000,0.98,-0.0068,-0.012,0.19,0.0097,0.012,0.018,0.003,-0.00063,0.0011,-0.0012,-0.0059,2.3e-05,0.002,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0013,0.0013,0.018,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 12190000,0.98,-0.0067,-0.012,0.19,0.0078,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,2.2e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0012,0.0012,0.018,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 12290000,0.98,-0.0068,-0.012,0.19,0.0055,0.011,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,2.2e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0012,0.0012,0.018,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12390000,0.98,-0.0069,-0.012,0.19,0.0041,0.0072,0.014,0.0017,0.00049,-0.0021,-0.0012,-0.006,2.1e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0011,0.0011,0.018,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12390000,0.98,-0.0069,-0.012,0.19,0.004,0.0072,0.014,0.0017,0.00049,-0.0021,-0.0012,-0.006,2.1e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0011,0.0011,0.018,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 12490000,0.98,-0.0069,-0.012,0.19,0.0041,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,2.1e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0011,0.0011,0.018,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 12590000,0.98,-0.0071,-0.012,0.19,0.0078,0.0015,0.02,0.0033,-0.0014,0.0017,-0.0011,-0.006,2e-05,0.0025,0.004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00098,0.00098,0.018,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12690000,0.98,-0.007,-0.012,0.19,0.0083,-0.00064,0.019,0.0041,-0.0013,0.0033,-0.0011,-0.006,2e-05,0.0025,0.004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.001,0.001,0.018,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.0041,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,1.8e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00093,0.00093,0.018,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12690000,0.98,-0.007,-0.012,0.19,0.0083,-0.00063,0.019,0.0041,-0.0013,0.0033,-0.0011,-0.006,2e-05,0.0025,0.004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.001,0.001,0.018,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.004,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,1.8e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00093,0.00093,0.018,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,1.8e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00096,0.00096,0.018,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 12990000,0.98,-0.0072,-0.012,0.19,0.0079,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,1.9e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00089,0.00089,0.018,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 13090000,0.98,-0.0073,-0.012,0.19,0.0088,-0.0028,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,1.9e-05,0.0027,0.0041,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00092,0.00092,0.018,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 @@ -135,10 +135,10 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 13290000,0.98,-0.0073,-0.012,0.19,0.0034,-0.0055,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,1.8e-05,0.0028,0.004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00089,0.00089,0.018,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 13390000,0.98,-0.0072,-0.012,0.19,0.0026,-0.0035,0.016,0.00083,-0.0037,0.0091,-0.0011,-0.006,1.9e-05,0.0028,0.0039,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 13490000,0.98,-0.0072,-0.012,0.19,0.003,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,1.9e-05,0.0029,0.0039,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00086,0.00086,0.018,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13590000,0.98,-0.0072,-0.012,0.19,0.0075,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,1.9e-05,0.0031,0.0037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.0088,0.048,0.048,0.044,3.8e-05,3.9e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13690000,0.98,-0.0072,-0.012,0.19,0.0075,-0.0035,0.017,0.0047,-0.0034,0.0064,-0.0011,-0.006,1.9e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00085,0.00085,0.018,0.061,0.061,0.0085,0.056,0.056,0.044,3.8e-05,3.9e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13790000,0.98,-0.0071,-0.012,0.19,0.014,0.0007,0.017,0.0083,-0.00094,0.0059,-0.0011,-0.0059,2e-05,0.0035,0.0037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.00081,0.018,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00083,0.0081,-0.0011,-0.0059,2e-05,0.0035,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13590000,0.98,-0.0072,-0.012,0.19,0.0075,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,1.9e-05,0.0031,0.0037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00082,0.00082,0.018,0.053,0.053,0.0088,0.048,0.048,0.044,3.8e-05,3.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13690000,0.98,-0.0072,-0.012,0.19,0.0075,-0.0035,0.017,0.0047,-0.0034,0.0064,-0.0011,-0.006,1.9e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00085,0.00085,0.018,0.061,0.061,0.0085,0.056,0.056,0.044,3.8e-05,3.8e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13790000,0.98,-0.0071,-0.012,0.19,0.014,0.00071,0.017,0.0083,-0.00094,0.0059,-0.0011,-0.0059,2e-05,0.0035,0.0037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.00081,0.018,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00082,0.0081,-0.0011,-0.0059,2e-05,0.0035,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00084,0.00084,0.018,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0015,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,1.9e-05,0.0033,0.0036,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0029,0.018,0.0088,-0.0024,0.0034,-0.0011,-0.006,1.9e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00083,0.00083,0.018,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 14190000,0.98,-0.0071,-0.011,0.19,0.0099,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,1.9e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.00079,0.018,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,6.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 @@ -146,110 +146,110 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,1.9e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.018,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0045,0.021,0.0094,-0.0036,0.015,-0.0011,-0.006,1.9e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00081,0.00081,0.018,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 14590000,0.98,-0.0073,-0.011,0.19,0.0078,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,1.8e-05,0.0031,0.0033,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00078,0.00078,0.018,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14690000,0.98,-0.0073,-0.011,0.19,0.007,-0.0046,0.019,0.0066,-0.0047,0.011,-0.0011,-0.006,1.8e-05,0.0031,0.0032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14790000,0.98,-0.0072,-0.011,0.19,0.0087,0.0024,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,2.1e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14890000,0.98,-0.0071,-0.011,0.19,0.0074,2.6e-05,0.023,0.006,0.00091,0.014,-0.0012,-0.006,2.1e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14990000,0.98,-0.0073,-0.011,0.19,0.0061,-0.0016,0.026,0.0047,-0.0007,0.017,-0.0012,-0.0061,2e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.018,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00055,0.03,0.0053,-0.00085,0.019,-0.0012,-0.0061,2e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.019,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15190000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0016,0.03,0.0042,-0.00077,0.021,-0.0012,-0.0061,2e-05,0.003,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00075,0.00075,0.019,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14690000,0.98,-0.0073,-0.011,0.19,0.0071,-0.0046,0.019,0.0066,-0.0047,0.011,-0.0011,-0.006,1.8e-05,0.0031,0.0032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14790000,0.98,-0.0072,-0.011,0.19,0.0087,0.0025,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,2.1e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00077,0.00077,0.018,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14890000,0.98,-0.0071,-0.011,0.19,0.0074,3.6e-05,0.023,0.006,0.00092,0.014,-0.0012,-0.006,2.1e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0008,0.0008,0.018,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.7e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14990000,0.98,-0.0072,-0.011,0.19,0.0061,-0.0016,0.026,0.0047,-0.0007,0.017,-0.0012,-0.0061,2e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.018,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00054,0.03,0.0053,-0.00085,0.019,-0.0012,-0.0061,2e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00079,0.00079,0.019,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15190000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0016,0.03,0.0042,-0.00076,0.021,-0.0012,-0.0061,2e-05,0.003,0.0038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00075,0.00075,0.019,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 15290000,0.98,-0.0074,-0.011,0.19,0.0049,-0.0027,0.03,0.0047,-0.00096,0.018,-0.0012,-0.0061,2e-05,0.0033,0.0035,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00078,0.00078,0.019,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15390000,0.98,-0.0075,-0.011,0.19,0.0051,-0.0003,0.029,0.0037,-0.00066,0.018,-0.0012,-0.0061,2e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00074,0.00074,0.019,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15490000,0.98,-0.0076,-0.011,0.19,0.0045,-0.0029,0.029,0.0042,-0.00079,0.019,-0.0012,-0.0061,2e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.019,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0067,0.029,0.0062,-0.0047,0.018,-0.0011,-0.0061,1.8e-05,0.0039,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0099,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,1.8e-05,0.004,0.0022,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00075,0.00075,0.019,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15790000,0.98,-0.0077,-0.011,0.19,0.0064,-0.0092,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,1.9e-05,0.0039,0.0025,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00072,0.00072,0.019,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15390000,0.98,-0.0075,-0.011,0.19,0.0051,-0.00029,0.029,0.0037,-0.00065,0.018,-0.0012,-0.0061,2e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00074,0.00074,0.019,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15490000,0.98,-0.0075,-0.011,0.19,0.0045,-0.0028,0.029,0.0042,-0.00078,0.019,-0.0012,-0.0061,2e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00076,0.00076,0.019,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0067,0.029,0.0062,-0.0047,0.018,-0.0011,-0.0061,1.8e-05,0.0038,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0098,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,1.8e-05,0.0039,0.0022,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00075,0.00075,0.019,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15790000,0.98,-0.0077,-0.011,0.19,0.0065,-0.0092,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,1.9e-05,0.0039,0.0025,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00072,0.00072,0.019,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0076,0.03,0.0061,-0.0052,0.02,-0.0011,-0.0061,1.9e-05,0.0041,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00073,0.00073,0.019,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.0061,0.027,0.0048,-0.004,0.019,-0.0012,-0.0061,1.9e-05,0.0043,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -16090000,0.98,-0.0076,-0.011,0.19,0.0026,-0.0074,0.024,0.0051,-0.0046,0.019,-0.0012,-0.0061,1.9e-05,0.0044,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00072,0.00072,0.019,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.005,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,2e-05,0.0045,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16290000,0.98,-0.0075,-0.011,0.19,-0.00099,-0.0065,0.023,0.0026,-0.004,0.017,-0.0012,-0.0061,2e-05,0.0046,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16390000,0.98,-0.0075,-0.011,0.19,0.0015,-0.0058,0.023,0.0036,-0.0031,0.017,-0.0012,-0.0061,2e-05,0.0051,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00067,0.00067,0.019,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16490000,0.98,-0.0076,-0.011,0.19,0.0034,-0.0074,0.026,0.0039,-0.0038,0.021,-0.0012,-0.0061,2e-05,0.005,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16090000,0.98,-0.0075,-0.011,0.19,0.0026,-0.0074,0.024,0.0051,-0.0046,0.019,-0.0012,-0.0061,1.9e-05,0.0044,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00072,0.00072,0.019,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.005,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,2e-05,0.0045,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16290000,0.98,-0.0075,-0.011,0.19,-0.00098,-0.0065,0.023,0.0026,-0.004,0.017,-0.0012,-0.0061,2e-05,0.0046,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0007,0.0007,0.019,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16390000,0.98,-0.0074,-0.011,0.19,0.0015,-0.0058,0.023,0.0036,-0.0031,0.017,-0.0012,-0.0061,2e-05,0.0051,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00067,0.00067,0.019,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16490000,0.98,-0.0075,-0.011,0.19,0.0035,-0.0074,0.026,0.0039,-0.0038,0.021,-0.0012,-0.0061,2e-05,0.005,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00068,0.00068,0.019,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0074,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,2.1e-05,0.0052,0.0025,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00065,0.019,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 16690000,0.98,-0.0076,-0.011,0.19,0.009,-0.012,0.029,0.0042,-0.0039,0.022,-0.0012,-0.0061,2.1e-05,0.0053,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00066,0.00066,0.019,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,6.3e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0028,0.022,-0.0012,-0.0061,2.1e-05,0.0054,0.0027,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00063,0.00063,0.019,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16890000,0.98,-0.0074,-0.011,0.19,0.0089,-0.011,0.029,0.0042,-0.0039,0.02,-0.0012,-0.0061,2.1e-05,0.0057,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00064,0.019,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16790000,0.98,-0.0074,-0.011,0.19,0.0099,-0.011,0.028,0.0033,-0.0028,0.022,-0.0012,-0.0061,2.1e-05,0.0054,0.0027,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00063,0.00063,0.019,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16890000,0.98,-0.0074,-0.011,0.19,0.0089,-0.011,0.029,0.0043,-0.0039,0.02,-0.0012,-0.0061,2.1e-05,0.0057,0.0024,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00065,0.00064,0.019,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 16990000,0.98,-0.0074,-0.011,0.19,0.0086,-0.011,0.029,0.004,-0.0029,0.019,-0.0013,-0.0061,2.2e-05,0.0063,0.0025,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00062,0.00061,0.019,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,2.2e-05,0.0065,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00063,0.00063,0.019,0.041,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17190000,0.98,-0.0076,-0.011,0.19,0.0089,-0.018,0.03,0.0033,-0.0076,0.021,-0.0012,-0.0061,2.1e-05,0.0063,0.0021,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0006,0.0006,0.019,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17290000,0.98,-0.0076,-0.011,0.19,0.0098,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,2.1e-05,0.0065,0.0019,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00061,0.00061,0.019,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,2.2e-05,0.0065,0.0023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00063,0.00063,0.019,0.04,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17190000,0.98,-0.0076,-0.011,0.19,0.009,-0.018,0.03,0.0033,-0.0076,0.021,-0.0012,-0.0061,2.1e-05,0.0063,0.0021,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.0006,0.0006,0.019,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17290000,0.98,-0.0076,-0.011,0.19,0.0099,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,2.1e-05,0.0065,0.0019,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.00061,0.00061,0.019,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 17390000,0.98,-0.0074,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,2.3e-05,0.0073,0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00058,0.00058,0.019,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17490000,0.98,-0.0075,-0.011,0.19,0.0046,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,2.3e-05,0.0074,0.0024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00059,0.00059,0.019,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17590000,0.98,-0.0074,-0.011,0.19,0.0008,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,2.4e-05,0.0072,0.0029,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00056,0.019,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17690000,0.98,-0.0075,-0.011,0.19,-0.00014,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,2.4e-05,0.0073,0.0029,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17790000,0.98,-0.0074,-0.011,0.19,0.0025,-0.014,0.029,0.0034,-0.0062,0.028,-0.0014,-0.006,2.5e-05,0.0076,0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00055,0.00055,0.019,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17890000,0.98,-0.0073,-0.011,0.19,0.0046,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,2.5e-05,0.0075,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17990000,0.98,-0.0071,-0.011,0.19,0.004,-0.0093,0.029,0.0031,-0.002,0.033,-0.0014,-0.006,2.7e-05,0.0079,0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17490000,0.98,-0.0075,-0.011,0.19,0.0047,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,2.3e-05,0.0074,0.0024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00059,0.00059,0.019,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,6.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17590000,0.98,-0.0073,-0.011,0.19,0.00084,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,2.4e-05,0.0072,0.0029,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00056,0.019,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17690000,0.98,-0.0074,-0.011,0.19,-0.00011,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,2.4e-05,0.0073,0.0029,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00057,0.00057,0.019,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17790000,0.98,-0.0074,-0.011,0.19,0.0025,-0.014,0.029,0.0035,-0.0062,0.028,-0.0014,-0.006,2.5e-05,0.0076,0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00055,0.00055,0.019,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17890000,0.98,-0.0073,-0.011,0.19,0.0047,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,2.5e-05,0.0075,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00056,0.00056,0.019,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17990000,0.98,-0.0071,-0.011,0.19,0.0041,-0.0093,0.029,0.0031,-0.002,0.033,-0.0014,-0.006,2.7e-05,0.0079,0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00053,0.019,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 18090000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0099,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,2.7e-05,0.0082,0.0044,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00054,0.00054,0.019,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0088,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,2.7e-05,0.0087,0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00052,0.00052,0.019,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 18290000,0.98,-0.0072,-0.011,0.19,0.0045,-0.0093,0.027,0.0045,-0.0031,0.027,-0.0014,-0.006,2.7e-05,0.009,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00053,0.00052,0.019,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,6.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,2.7e-05,0.0096,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.0005,0.019,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18490000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0081,0.026,0.0069,-0.0032,0.028,-0.0014,-0.006,2.7e-05,0.0096,0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.00051,0.019,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18590000,0.98,-0.007,-0.011,0.19,0.0065,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,2.8e-05,0.0095,0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00049,0.019,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0064,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,2.8e-05,0.0097,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0005,0.0005,0.019,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,2.8e-05,0.01,0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00048,0.019,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18390000,0.98,-0.0071,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,2.7e-05,0.0096,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.0005,0.019,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18490000,0.98,-0.0072,-0.011,0.19,0.0082,-0.0081,0.026,0.0069,-0.0032,0.028,-0.0014,-0.006,2.7e-05,0.0096,0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00051,0.00051,0.019,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,6.3e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18590000,0.98,-0.007,-0.011,0.19,0.0066,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,2.8e-05,0.0095,0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00049,0.019,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0063,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,2.8e-05,0.0097,0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0005,0.0005,0.019,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18790000,0.98,-0.0069,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,2.8e-05,0.01,0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00048,0.019,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 18890000,0.98,-0.0069,-0.011,0.19,0.0043,-0.0057,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,2.8e-05,0.01,0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00049,0.00048,0.019,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 18990000,0.98,-0.0069,-0.011,0.19,0.0026,-0.0058,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,2.8e-05,0.01,0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00047,0.00047,0.019,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19090000,0.98,-0.007,-0.011,0.19,0.0006,-0.0063,0.023,0.0057,-0.0031,0.022,-0.0015,-0.006,2.8e-05,0.011,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00047,0.019,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19190000,0.98,-0.0069,-0.011,0.19,-0.00087,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,2.8e-05,0.011,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19290000,0.98,-0.0068,-0.011,0.19,-0.0017,-0.0058,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,2.8e-05,0.011,0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19090000,0.98,-0.007,-0.011,0.19,0.00063,-0.0063,0.023,0.0057,-0.0031,0.022,-0.0015,-0.006,2.8e-05,0.011,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00048,0.00047,0.019,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19190000,0.98,-0.0069,-0.011,0.19,-0.00085,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,2.8e-05,0.011,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19290000,0.98,-0.0068,-0.011,0.19,-0.0017,-0.0058,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,2.8e-05,0.011,0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00046,0.00046,0.019,0.031,0.031,0.0087,0.05,0.05,0.036,3.7e-06,3.7e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 19390000,0.98,-0.0069,-0.011,0.19,-0.0022,-0.0023,0.024,0.004,-0.0012,0.019,-0.0015,-0.006,2.9e-05,0.011,0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19490000,0.98,-0.007,-0.011,0.19,-0.003,-0.0023,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,2.9e-05,0.011,0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19490000,0.98,-0.0069,-0.011,0.19,-0.003,-0.0023,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,2.9e-05,0.011,0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00045,0.019,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0052,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,2.9e-05,0.012,0.0032,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00044,0.019,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19690000,0.98,-0.0069,-0.011,0.19,-0.0058,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,2.9e-05,0.012,0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00044,0.019,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19690000,0.98,-0.0069,-0.011,0.19,-0.0057,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,2.9e-05,0.012,0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00045,0.00044,0.019,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,6.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 19790000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0023,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,2.9e-05,0.012,0.0028,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00043,0.019,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,2.9e-05,0.013,0.0027,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00043,0.019,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0019,0.019,0.0061,-0.00092,0.0097,-0.0015,-0.0059,2.9e-05,0.013,0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00042,0.019,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +19890000,0.98,-0.007,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,2.9e-05,0.013,0.0027,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00044,0.00043,0.019,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,6.3e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.002,0.019,0.0061,-0.00093,0.0097,-0.0015,-0.0059,2.9e-05,0.013,0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00042,0.019,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0042,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00043,0.00042,0.019,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 20190000,0.98,-0.0071,-0.011,0.19,-0.0039,-0.0016,0.02,0.0065,-0.00092,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00041,0.019,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20290000,0.98,-0.0071,-0.011,0.19,-0.0071,-0.0027,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00078,0.014,-0.0015,-0.0059,3e-05,0.014,0.0024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0025,0.02,0.0059,-0.00096,0.012,-0.0015,-0.0059,3e-05,0.014,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.0069,-0.0008,0.011,-0.0015,-0.0059,3e-05,0.014,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.0004,0.019,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20290000,0.98,-0.007,-0.011,0.19,-0.0071,-0.0027,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,2.9e-05,0.013,0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00042,0.00042,0.019,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00079,0.014,-0.0015,-0.0059,3e-05,0.014,0.0024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0025,0.02,0.0059,-0.00097,0.012,-0.0015,-0.0059,3e-05,0.014,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.00041,0.019,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.0069,-0.00081,0.011,-0.0015,-0.0059,3e-05,0.014,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.0004,0.019,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,3e-05,0.014,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00041,0.0004,0.019,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00039,0.0055,0.0048,-0.00082,0.0097,-0.0015,-0.0059,3e-05,0.015,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.00039,0.019,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.00014,0.0034,-0.0015,-0.0059,3e-05,0.015,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.00039,0.019,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.00051,-0.011,-0.0015,-0.0059,3e-05,0.015,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00034,0.0055,0.0048,-0.00083,0.0097,-0.0015,-0.0059,3e-05,0.015,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.00039,0.019,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.00016,0.0034,-0.0015,-0.0059,3e-05,0.015,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.0004,0.00039,0.019,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.0005,-0.011,-0.0015,-0.0059,3e-05,0.015,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,3e-05,0.015,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00039,0.019,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0013,0.0035,-0.078,-0.0014,-0.0059,2.9e-05,0.015,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00038,0.019,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.98,-0.00051,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0087,-0.14,-0.0014,-0.0059,2.9e-05,0.015,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00038,0.019,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.98,-0.002,-0.0079,0.19,-0.045,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,2.9e-05,0.015,0.00077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00037,0.019,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.29,-0.0014,-0.0059,2.9e-05,0.015,0.00067,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00037,0.019,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.98,-0.0005,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0087,-0.14,-0.0014,-0.0059,2.9e-05,0.015,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00039,0.00038,0.019,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.98,-0.002,-0.0079,0.19,-0.045,0.05,-0.75,-0.0051,0.011,-0.2,-0.0014,-0.0059,2.9e-05,0.015,0.00077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00037,0.019,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0094,0.016,-0.29,-0.0014,-0.0059,2.9e-05,0.015,0.00067,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00038,0.00037,0.019,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 21590000,0.98,-0.0033,-0.0083,0.19,-0.032,0.043,-1,-0.008,0.016,-0.38,-0.0014,-0.0059,2.9e-05,0.015,0.00063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.019,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,2.9e-05,0.015,0.00046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.019,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,2.9e-05,0.016,0.00027,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-0.0014,-0.0058,2.9e-05,0.016,0.00013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00038,0.017,-0.89,-0.0014,-0.0058,2.9e-05,0.015,0.00038,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0082,0.043,0.043,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,2.9e-05,0.016,0.00025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0082,0.048,0.048,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,2.9e-05,0.016,0.00029,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +21690000,0.98,-0.0036,-0.0082,0.19,-0.03,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,2.9e-05,0.015,0.00046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00037,0.00037,0.019,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.032,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,2.9e-05,0.016,0.00027,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0058,0.021,-0.75,-0.0014,-0.0058,2.9e-05,0.016,0.00014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00036,0.02,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,6.3e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.022,-1.4,-0.00041,0.017,-0.89,-0.0014,-0.0058,2.9e-05,0.015,0.00038,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00035,0.02,0.022,0.022,0.0082,0.043,0.043,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,2.9e-05,0.016,0.00026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00036,0.00035,0.02,0.024,0.024,0.0082,0.048,0.048,0.036,1.2e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22190000,0.98,-0.0061,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,2.9e-05,0.016,0.00029,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0079,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,2.9e-05,0.016,0.00019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00035,0.02,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22390000,0.98,-0.0072,-0.01,0.19,0.0066,-0.0017,-1.4,0.013,0.0042,-1.5,-0.0014,-0.0058,2.8e-05,0.016,-0.00016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22390000,0.98,-0.0072,-0.01,0.19,0.0066,-0.0017,-1.4,0.013,0.0041,-1.5,-0.0014,-0.0058,2.8e-05,0.016,-0.00015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,2.8e-05,0.016,-0.0002,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00035,0.00034,0.02,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,2.8e-05,0.016,-0.00036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,2.8e-05,0.016,-0.00044,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.021,0.021,0.0081,0.047,0.047,0.036,9.5e-07,9.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,2.8e-05,0.016,-0.00056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.02,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.034,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,2.8e-05,0.016,-0.00064,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.02,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,2.9e-05,0.017,-0.00077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22890000,0.98,-0.0074,-0.012,0.19,0.032,-0.034,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,2.8e-05,0.016,-0.00063,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.02,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22990000,0.98,-0.0073,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,2.9e-05,0.017,-0.00076,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,2.9e-05,0.017,-0.0008,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.02,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,2.9e-05,0.017,-0.00095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.008,0.042,0.042,0.035,8e-07,8e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,2.9e-05,0.017,-0.001,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,2.9e-05,0.017,-0.00075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.008,0.041,0.041,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23490000,0.98,-0.0079,-0.014,0.19,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,2.9e-05,0.017,-0.00079,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23490000,0.98,-0.0079,-0.014,0.19,0.062,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,2.9e-05,0.017,-0.00079,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23590000,0.98,-0.0081,-0.014,0.19,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,3e-05,0.017,-0.00091,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23690000,0.98,-0.0088,-0.014,0.19,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0058,3e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23690000,0.98,-0.0088,-0.014,0.19,0.062,-0.06,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0058,3e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23790000,0.98,-0.011,-0.017,0.19,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,2.9e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23890000,0.98,-0.014,-0.021,0.19,0.053,-0.058,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,2.9e-05,0.017,-0.00094,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.02,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 23990000,0.98,-0.016,-0.024,0.19,0.054,-0.058,-0.14,0.13,-0.089,-3.6,-0.0014,-0.0058,2.9e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 24090000,0.98,-0.016,-0.023,0.19,0.061,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,2.9e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00034,0.02,0.017,0.017,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 24190000,0.98,-0.013,-0.019,0.19,0.072,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,3e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.015,0.015,0.008,0.04,0.04,0.035,6.4e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24290000,0.98,-0.01,-0.016,0.19,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,3e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.016,0.016,0.0081,0.044,0.044,0.036,6.4e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24390000,0.98,-0.0096,-0.015,0.19,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24490000,0.98,-0.0098,-0.015,0.19,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24290000,0.98,-0.01,-0.016,0.19,0.076,-0.074,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,3e-05,0.019,-0.0022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.02,0.016,0.016,0.0081,0.044,0.044,0.036,6.4e-07,6.3e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24390000,0.98,-0.0095,-0.015,0.19,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24490000,0.98,-0.0098,-0.015,0.19,0.065,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 24590000,0.98,-0.01,-0.015,0.19,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 24690000,0.98,-0.011,-0.015,0.19,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,2.9e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 24790000,0.98,-0.011,-0.014,0.19,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 24890000,0.98,-0.011,-0.013,0.19,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24990000,0.98,-0.011,-0.013,0.19,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24990000,0.98,-0.011,-0.013,0.19,0.046,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 25090000,0.98,-0.011,-0.013,0.19,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,2.9e-05,0.019,-0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,6.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 25190000,0.98,-0.011,-0.013,0.19,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,3e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,6.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 25290000,0.98,-0.011,-0.012,0.19,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,3e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 @@ -258,94 +258,94 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 25590000,0.98,-0.011,-0.012,0.19,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,3.1e-05,0.018,-0.0065,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 25690000,0.98,-0.011,-0.011,0.19,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,3.1e-05,0.018,-0.0066,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.016,0.0081,0.043,0.043,0.035,5e-07,5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 25790000,0.98,-0.011,-0.011,0.19,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,3.2e-05,0.018,-0.007,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.014,0.014,0.008,0.039,0.039,0.035,4.9e-07,4.8e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25890000,0.98,-0.011,-0.011,0.19,-0.0037,-0.029,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,3.2e-05,0.018,-0.007,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.0081,0.043,0.043,0.036,4.9e-07,4.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25890000,0.98,-0.011,-0.011,0.19,-0.0036,-0.029,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,3.2e-05,0.018,-0.007,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.015,0.015,0.0081,0.043,0.043,0.036,4.9e-07,4.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,3.3e-05,0.018,-0.0075,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.02,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 26090000,0.98,-0.01,-0.011,0.19,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0075,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00033,0.02,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 26190000,0.98,-0.01,-0.011,0.19,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00033,0.02,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 26290000,0.98,-0.01,-0.012,0.19,-0.026,-0.014,0.00052,0.15,-0.083,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26390000,0.98,-0.0098,-0.012,0.19,-0.032,-0.0065,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.008,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.014,0.014,0.008,0.038,0.038,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26490000,0.98,-0.0096,-0.011,0.19,-0.035,-0.0034,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0079,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26590000,0.98,-0.009,-0.012,0.19,-0.036,0.0046,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.3e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26690000,0.98,-0.0089,-0.011,0.19,-0.038,0.0097,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0081,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.4e-07,4.4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26790000,0.98,-0.0087,-0.011,0.19,-0.045,0.013,0.012,0.1,-0.062,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26890000,0.98,-0.008,-0.011,0.19,-0.051,0.016,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.036,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.98,-0.0098,-0.012,0.19,-0.032,-0.0067,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.008,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.02,0.014,0.014,0.008,0.038,0.038,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.98,-0.0095,-0.011,0.19,-0.035,-0.0035,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0079,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.98,-0.009,-0.012,0.19,-0.036,0.0044,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.3e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.98,-0.0088,-0.011,0.19,-0.038,0.0095,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.4e-07,4.4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.98,-0.0086,-0.011,0.19,-0.045,0.013,0.012,0.1,-0.062,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.98,-0.008,-0.011,0.19,-0.051,0.016,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.036,4.3e-07,4.2e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 26990000,0.98,-0.0075,-0.011,0.19,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 27090000,0.98,-0.0073,-0.012,0.19,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.2e-07,4.1e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27190000,0.98,-0.0074,-0.012,0.19,-0.066,0.035,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27190000,0.98,-0.0073,-0.012,0.19,-0.066,0.035,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 27290000,0.98,-0.0075,-0.013,0.19,-0.073,0.041,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,3.3e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00032,0.021,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 27390000,0.98,-0.0089,-0.015,0.19,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,3.5e-05,0.02,-0.0092,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,4e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 27490000,0.98,-0.01,-0.017,0.19,-0.082,0.053,0.76,0.047,-0.03,-3.5,-0.0016,-0.0058,3.5e-05,0.02,-0.0093,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.042,0.042,0.035,4e-07,4e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27590000,0.98,-0.01,-0.016,0.19,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,3.5e-05,0.02,-0.0094,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27590000,0.98,-0.01,-0.016,0.19,-0.076,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,3.5e-05,0.02,-0.0094,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 27690000,0.98,-0.0089,-0.013,0.19,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,3.5e-05,0.02,-0.0095,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,6.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27790000,0.98,-0.0076,-0.011,0.19,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,3.5e-05,0.02,-0.0089,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27890000,0.98,-0.0072,-0.012,0.19,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,3.5e-05,0.02,-0.009,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27790000,0.98,-0.0076,-0.011,0.19,-0.071,0.049,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,3.5e-05,0.02,-0.0089,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27890000,0.98,-0.0072,-0.012,0.19,-0.078,0.056,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,3.5e-05,0.02,-0.009,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 27990000,0.98,-0.0077,-0.012,0.19,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,3.6e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28090000,0.98,-0.008,-0.012,0.19,-0.082,0.059,0.78,0.0042,-0.0047,-3,-0.0016,-0.0058,3.6e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.8e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28190000,0.98,-0.0074,-0.012,0.19,-0.082,0.055,0.79,-0.0023,-0.0043,-3,-0.0016,-0.0058,3.6e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28290000,0.98,-0.0069,-0.012,0.19,-0.088,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,3.6e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28390000,0.98,-0.0069,-0.013,0.19,-0.088,0.061,0.79,-0.015,0.0045,-2.8,-0.0015,-0.0058,3.8e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28490000,0.98,-0.0072,-0.014,0.19,-0.09,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,3.8e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0085,-2.7,-0.0015,-0.0058,3.8e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28090000,0.98,-0.0079,-0.012,0.19,-0.082,0.059,0.78,0.0042,-0.0048,-3,-0.0016,-0.0058,3.6e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.8e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28190000,0.98,-0.0074,-0.012,0.19,-0.082,0.055,0.79,-0.0023,-0.0044,-3,-0.0016,-0.0058,3.6e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28290000,0.98,-0.0069,-0.012,0.19,-0.088,0.059,0.79,-0.011,0.0014,-2.9,-0.0016,-0.0058,3.6e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28390000,0.98,-0.0069,-0.013,0.19,-0.088,0.061,0.79,-0.015,0.0044,-2.8,-0.0015,-0.0058,3.8e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28490000,0.98,-0.0072,-0.014,0.19,-0.09,0.065,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,3.8e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28590000,0.98,-0.0072,-0.014,0.19,-0.083,0.06,0.79,-0.027,0.0084,-2.7,-0.0015,-0.0058,3.8e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 28690000,0.98,-0.007,-0.013,0.19,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,3.8e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.6e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,4e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,4e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,4.2e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,4.2e-05,0.019,-0.0086,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,4.5e-05,0.02,-0.0088,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.2,-0.0015,-0.0058,4.5e-05,0.02,-0.0089,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.066,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,4.8e-05,0.02,-0.009,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,4.8e-05,0.02,-0.009,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,5e-05,0.02,-0.0092,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29690000,0.98,-0.0065,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,5e-05,0.02,-0.0094,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29790000,0.98,-0.0063,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,5.2e-05,0.02,-0.0096,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,5.2e-05,0.02,-0.0098,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29990000,0.98,-0.006,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,5.4e-05,0.02,-0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30090000,0.98,-0.0061,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,5.4e-05,0.02,-0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30190000,0.98,-0.0061,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,5.6e-05,0.02,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30290000,0.98,-0.0061,-0.013,0.18,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,5.6e-05,0.021,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30390000,0.98,-0.0061,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.4,-0.0014,-0.0057,5.9e-05,0.021,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,5.9e-05,0.021,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28790000,0.98,-0.0064,-0.013,0.19,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,4e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28890000,0.98,-0.0062,-0.012,0.19,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,4e-05,0.019,-0.0085,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28990000,0.98,-0.006,-0.013,0.19,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,4.2e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29090000,0.98,-0.0058,-0.013,0.19,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,4.2e-05,0.019,-0.0086,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29190000,0.98,-0.0058,-0.013,0.19,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,4.5e-05,0.02,-0.0088,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29290000,0.98,-0.006,-0.013,0.19,-0.08,0.067,0.78,-0.059,0.033,-2.2,-0.0015,-0.0058,4.5e-05,0.02,-0.0089,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29390000,0.98,-0.0065,-0.012,0.19,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,4.8e-05,0.02,-0.009,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29490000,0.98,-0.0065,-0.012,0.19,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,4.8e-05,0.02,-0.0091,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.0081,0.041,0.041,0.036,3.4e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29590000,0.98,-0.0064,-0.012,0.19,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,5e-05,0.02,-0.0093,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29690000,0.98,-0.0065,-0.012,0.19,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,5e-05,0.02,-0.0094,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29790000,0.98,-0.0063,-0.013,0.19,-0.074,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,5.2e-05,0.02,-0.0096,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29890000,0.98,-0.0058,-0.013,0.19,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,5.2e-05,0.02,-0.0098,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29990000,0.98,-0.0059,-0.013,0.19,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,5.4e-05,0.02,-0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30090000,0.98,-0.0061,-0.013,0.19,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,5.4e-05,0.02,-0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30190000,0.98,-0.0061,-0.013,0.19,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,5.6e-05,0.02,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30290000,0.98,-0.0061,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,5.6e-05,0.021,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,5.9e-05,0.021,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30490000,0.98,-0.0061,-0.013,0.19,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,5.9e-05,0.021,-0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 30590000,0.98,-0.0064,-0.013,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,6.1e-05,0.021,-0.012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,6.1e-05,0.021,-0.012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.013,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,6.3e-05,0.022,-0.012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30890000,0.98,-0.0059,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,6.3e-05,0.022,-0.012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.041,0.041,0.035,3.1e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30990000,0.98,-0.0061,-0.013,0.18,-0.036,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,6.4e-05,0.022,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31090000,0.98,-0.0062,-0.013,0.18,-0.035,0.025,0.76,-0.06,0.051,-0.86,-0.0014,-0.0057,6.4e-05,0.022,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.041,0.04,0.036,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,6.3e-05,0.022,-0.012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.014,0.013,0.008,0.041,0.041,0.035,3.1e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,6.4e-05,0.022,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31090000,0.98,-0.0062,-0.013,0.18,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,6.4e-05,0.022,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.021,0.013,0.013,0.008,0.041,0.04,0.036,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 31190000,0.98,-0.0064,-0.013,0.18,-0.031,0.02,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,6.6e-05,0.022,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,6.6e-05,0.022,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,6.7e-05,0.023,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 31490000,0.98,-0.0061,-0.014,0.18,-0.022,0.0088,0.76,-0.048,0.043,-0.58,-0.0014,-0.0057,6.7e-05,0.023,-0.013,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0066,0.76,-0.037,0.039,-0.51,-0.0014,-0.0057,6.8e-05,0.023,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0065,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,6.8e-05,0.023,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 31690000,0.98,-0.006,-0.015,0.18,-0.02,0.0055,0.76,-0.039,0.039,-0.44,-0.0014,-0.0057,6.8e-05,0.023,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0029,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,7e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31890000,0.98,-0.0059,-0.015,0.18,-0.0081,0.00056,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,7e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31990000,0.98,-0.0062,-0.015,0.18,-0.00018,-0.00011,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,7.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32090000,0.98,-0.0066,-0.014,0.18,-0.00074,-0.0035,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,7.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32190000,0.98,-0.0068,-0.015,0.18,0.0046,-0.0067,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,7.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32290000,0.98,-0.0067,-0.015,0.18,0.0062,-0.0095,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,7.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32390000,0.98,-0.0068,-0.015,0.18,0.012,-0.011,0.75,0.0058,0.03,0.051,-0.0013,-0.0057,7.4e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.074,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,7.4e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.022,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00057,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,7e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31990000,0.98,-0.0062,-0.015,0.18,-0.00014,-9.7e-05,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,7.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32090000,0.98,-0.0066,-0.014,0.18,-0.00069,-0.0035,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,7.1e-05,0.024,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32190000,0.98,-0.0067,-0.015,0.18,0.0046,-0.0067,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,7.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32290000,0.98,-0.0066,-0.015,0.18,0.0062,-0.0094,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,7.2e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32390000,0.98,-0.0068,-0.015,0.18,0.012,-0.011,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,7.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00034,0.00033,0.022,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.074,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,7.3e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.022,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 32590000,0.98,-0.0096,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,7.5e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.022,0.016,0.016,0.0075,0.037,0.037,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32690000,0.98,-0.0096,-0.013,0.18,0.035,-0.081,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,7.5e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.022,0.019,0.019,0.0074,0.041,0.041,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.081,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,7.5e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00033,0.00033,0.022,0.019,0.019,0.0074,0.041,0.041,0.035,2.8e-07,2.8e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 32790000,0.98,-0.0092,-0.013,0.18,0.033,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0056,7.6e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.022,0.019,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 32890000,0.98,-0.0092,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.0019,-0.011,-0.0014,-0.0056,7.6e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00032,0.00032,0.022,0.023,0.024,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0013,-0.024,-0.0014,-0.0056,7.7e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.0003,0.022,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0012,-0.024,-0.0014,-0.0056,7.7e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.0003,0.022,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 33090000,0.98,-0.0089,-0.013,0.18,0.026,-0.084,-0.12,0.048,-0.0094,-0.031,-0.0014,-0.0056,7.7e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0003,0.0003,0.022,0.029,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 33190000,0.98,-0.0086,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,7.8e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00028,0.00028,0.022,0.029,0.029,0.0064,0.038,0.038,0.035,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33290000,0.98,-0.0086,-0.013,0.18,0.018,-0.081,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,7.8e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00028,0.00028,0.022,0.035,0.035,0.0063,0.043,0.043,0.034,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33390000,0.98,-0.0082,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,8e-05,0.025,-0.016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00025,0.00025,0.022,0.035,0.035,0.0062,0.039,0.039,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33490000,0.98,-0.0081,-0.013,0.18,0.0091,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,8e-05,0.025,-0.016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00025,0.00025,0.022,0.042,0.042,0.0061,0.044,0.044,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33590000,0.98,-0.0078,-0.013,0.18,0.0053,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,8.1e-05,0.024,-0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00022,0.022,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 -33690000,0.98,-0.0078,-0.013,0.18,0.00057,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,8.1e-05,0.024,-0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00022,0.022,0.048,0.048,0.0059,0.046,0.046,0.034,2.7e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 -33790000,0.98,-0.0075,-0.013,0.18,-0.0025,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,8.2e-05,0.023,-0.021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00019,0.022,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33890000,0.98,-0.0075,-0.013,0.18,-0.0067,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,8.2e-05,0.023,-0.021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00019,0.022,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33990000,0.98,-0.0072,-0.013,0.18,-0.0063,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,8.2e-05,0.02,-0.024,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00018,0.00017,0.022,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.081,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,7.8e-05,0.025,-0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00028,0.00028,0.022,0.035,0.035,0.0063,0.043,0.043,0.034,2.7e-07,2.7e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,8e-05,0.025,-0.016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00025,0.00025,0.022,0.035,0.035,0.0062,0.039,0.039,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33490000,0.98,-0.0081,-0.013,0.18,0.0093,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,8e-05,0.025,-0.016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00025,0.00025,0.022,0.042,0.042,0.0061,0.044,0.044,0.034,2.7e-07,2.6e-07,6.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33590000,0.98,-0.0078,-0.013,0.18,0.0054,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,8.1e-05,0.024,-0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00022,0.022,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 +33690000,0.98,-0.0077,-0.013,0.18,0.00074,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,8.1e-05,0.024,-0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00022,0.00022,0.022,0.048,0.048,0.0059,0.046,0.046,0.034,2.7e-07,2.6e-07,6.4e-06,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 +33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,8.2e-05,0.023,-0.022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00019,0.022,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,8.2e-05,0.023,-0.021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.0002,0.00019,0.022,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,6.4e-06,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,8.2e-05,0.02,-0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00018,0.00017,0.022,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,8.2e-05,0.02,-0.024,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00018,0.00017,0.022,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,6.4e-06,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,8.3e-05,0.019,-0.026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00016,0.00015,0.022,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,6.4e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 34290000,0.98,-0.007,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,8.3e-05,0.018,-0.026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00016,0.00015,0.022,0.055,0.055,0.0058,0.05,0.05,0.033,2.7e-07,2.6e-07,6.4e-06,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 34390000,0.98,-0.0069,-0.013,0.18,-0.013,-0.01,-0.092,0.072,-0.01,-0.11,-0.0014,-0.0056,8.3e-05,0.017,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00015,0.00014,0.022,0.047,0.047,0.0058,0.044,0.044,0.033,2.7e-07,2.6e-07,6.4e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,7e-05,0.017,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00014,0.00014,0.018,0.053,0.054,0.0059,0.051,0.051,0.032,2.7e-07,2.6e-07,6.1e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0048,0.71,0.073,-0.0088,-0.081,-0.0014,-0.0056,7e-05,0.016,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00013,0.018,0.044,0.044,0.0059,0.045,0.045,0.032,2.7e-07,2.6e-07,6.1e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34690000,0.98,-0.0069,-0.012,0.18,-0.017,-0.0026,1.7,0.071,-0.0092,0.038,-0.0014,-0.0056,7e-05,0.016,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00013,0.018,0.047,0.048,0.006,0.052,0.052,0.032,2.7e-07,2.6e-07,6.1e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34790000,0.98,-0.0069,-0.012,0.18,-0.018,0.002,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,7e-05,0.017,-0.03,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00012,0.018,0.04,0.04,0.0061,0.045,0.045,0.032,2.7e-07,2.7e-07,6.1e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 -34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0045,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,7e-05,0.017,-0.03,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00012,0.018,0.044,0.044,0.0061,0.052,0.052,0.032,2.7e-07,2.7e-07,6.1e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 +34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,7.4e-05,0.017,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00014,0.00014,0.018,0.053,0.054,0.0059,0.051,0.051,0.032,2.7e-07,2.6e-07,6.1e-06,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0049,0.71,0.073,-0.0088,-0.081,-0.0014,-0.0056,7.4e-05,0.016,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00013,0.018,0.044,0.044,0.0059,0.045,0.045,0.032,2.7e-07,2.6e-07,6.1e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34690000,0.98,-0.0069,-0.012,0.18,-0.017,-0.0027,1.7,0.071,-0.0092,0.038,-0.0014,-0.0056,7.4e-05,0.016,-0.028,-0.11,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00013,0.018,0.047,0.048,0.006,0.052,0.052,0.032,2.7e-07,2.6e-07,6.1e-06,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34790000,0.98,-0.0068,-0.012,0.18,-0.018,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,7.4e-05,0.017,-0.03,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00012,0.018,0.04,0.04,0.0061,0.045,0.045,0.032,2.7e-07,2.7e-07,6.1e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 +34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0044,3.6,0.07,-0.0064,0.5,-0.0014,-0.0056,7.4e-05,0.017,-0.03,-0.1,0.37,0.0037,0.026,0,0,0,0,0,0.00013,0.00012,0.018,0.044,0.044,0.0061,0.052,0.052,0.032,2.7e-07,2.7e-07,6.1e-06,0.021,0.021,0.0005,0,0,0,0,0,0,0,0