diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 9d1f77403a..92aef646ec 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -39,6 +39,8 @@ bool cs_rng_kin_consistent # 31 - true when the range finder kinematic cons bool cs_fake_pos # 32 - true when fake position measurements are being fused bool cs_fake_hgt # 33 - true when fake height measurements are being fused bool cs_gravity_vector # 34 - true when gravity vector measurements are being fused +bool cs_mag # 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended +bool cs_ev_yaw_fault # 36 - true when the EV heading has been declared faulty and is no longer being used # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 6a44bd1d19..0f1c095890 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -84,8 +84,10 @@ list(APPEND EKF_SRCS EKF/gravity_fusion.cpp EKF/height_control.cpp EKF/imu_down_sampler.cpp + EKF/mag_3d_control.cpp EKF/mag_control.cpp EKF/mag_fusion.cpp + EKF/mag_heading_control.cpp EKF/output_predictor.cpp EKF/vel_pos_fusion.cpp EKF/zero_innovation_heading_update.cpp diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 2e8960f0f5..64230774af 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2015-2018 ECL Development Team. All rights reserved. +# Copyright (c) 2015-2023 ECL Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -49,8 +49,10 @@ list(APPEND EKF_SRCS gravity_fusion.cpp height_control.cpp imu_down_sampler.cpp + mag_3d_control.cpp mag_control.cpp mag_fusion.cpp + mag_heading_control.cpp output_predictor.cpp vel_pos_fusion.cpp zero_innovation_heading_update.cpp diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 69ab710dd5..15de4bebd5 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -102,9 +102,6 @@ enum MagFuseType : uint8_t { // Integer definitions for mag_fusion_type AUTO = 0, ///< The selection of either heading or 3D magnetometer fusion will be automatic HEADING = 1, ///< Simple yaw angle fusion will always be used. This is less accurate, but less affected by earth field distortions. It should not be used for pitch angles outside the range from -60 to +60 deg - MAG_3D = 2, ///< Magnetometer 3-axis fusion will always be used. This is more accurate, but more affected by localised earth field distortions - UNUSED = 3, ///< Not implemented - INDOOR = 4, ///< The same as option 0, but magnetometer or yaw fusion will not be used unless earth frame external aiding (GPS or External Vision) is being used. This prevents inconsistent magnetic fields associated with indoor operation degrading state estimates. NONE = 5 ///< Do not use magnetometer under any circumstance.. }; @@ -335,7 +332,7 @@ struct parameters { // magnetometer fusion float mag_heading_noise{3.0e-1f}; ///< measurement noise used for simple heading fusion (rad) - float mag_noise{5.0e-2f}; ///< measurement noise used for 3-axis magnetoemeter fusion (Gauss) + float mag_noise{5.0e-2f}; ///< measurement noise used for 3-axis magnetometer fusion (Gauss) float mag_declination_deg{0.0f}; ///< magnetic declination (degrees) float heading_innov_gate{2.6f}; ///< heading fusion innovation consistency gate size (STD) float mag_innov_gate{3.0f}; ///< magnetometer fusion innovation consistency gate size (STD) @@ -601,6 +598,9 @@ union filter_control_status_u { uint64_t fake_pos : 1; ///< 32 - true when fake position measurements are being fused uint64_t fake_hgt : 1; ///< 33 - true when fake height measurements are being fused uint64_t gravity_vector : 1; ///< 34 - true when gravity vector measurements are being fused + uint64_t mag : 1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended + uint64_t ev_yaw_fault : 1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used + } flags; uint64_t value; }; diff --git a/src/modules/ekf2/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp index 8eddf1c285..c35563135c 100644 --- a/src/modules/ekf2/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -76,7 +76,7 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) _control_status.flags.tilt_align = true; // send alignment status message to the console - const char *height_source = nullptr; + const char *height_source = "unknown"; if (_control_status.flags.baro_hgt) { height_source = "baro"; @@ -89,16 +89,16 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) } else if (_control_status.flags.rng_hgt) { height_source = "rng"; - - } else { - height_source = "unknown"; - } - if (height_source) { - ECL_INFO("%llu: EKF aligned, (%s hgt, IMU buf: %i, OBS buf: %i)", + ECL_INFO("%llu: EKF aligned, (%s hgt, IMU buf: %i, OBS buf: %i)", (unsigned long long)imu_delayed.time_us, height_source, (int)_imu_buffer_length, (int)_obs_buffer_length); - } + + ECL_DEBUG("tilt aligned, roll: %.3f, pitch %.3f, yaw: %.3f", + (double)matrix::Eulerf(_state.quat_nominal).phi(), + (double)matrix::Eulerf(_state.quat_nominal).theta(), + (double)matrix::Eulerf(_state.quat_nominal).psi() + ); } } diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 4afa3698bc..9f8371b533 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -180,7 +180,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // Don't continue to grow the earth field variances if they are becoming too large or we are not doing 3-axis fusion as this can make the covariance matrix badly conditioned float mag_I_sig; - if (_control_status.flags.mag_3D && (P(16, 16) + P(17, 17) + P(18, 18)) < 0.1f) { + if (_control_status.flags.mag && (P(16, 16) + P(17, 17) + P(18, 18)) < 0.1f) { mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.0f, 1.0f); } else { @@ -190,7 +190,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) // Don't continue to grow the body field variances if they is becoming too large or we are not doing 3-axis fusion as this can make the covariance matrix badly conditioned float mag_B_sig; - if (_control_status.flags.mag_3D && (P(19, 19) + P(20, 20) + P(21, 21)) < 0.1f) { + if (_control_status.flags.mag && (P(19, 19) + P(20, 20) + P(21, 21)) < 0.1f) { mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.0f, 1.0f); } else { @@ -292,7 +292,7 @@ void Ekf::predictCovariance(const imuSample &imu_delayed) P(row, row) = nextP(row, row); } - if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag) { for (unsigned row = 16; row <= 21; row++) { for (unsigned column = 0 ; column < row; column++) { P(row, column) = P(column, row) = nextP(column, row); @@ -471,8 +471,9 @@ void Ekf::fixCovarianceErrors(bool force_symmetry) } // magnetic field states - if (!_control_status.flags.mag_3D) { - zeroMagCov(); + if (!_control_status.flags.mag) { + P.uncorrelateCovarianceSetVariance<3>(16, 0.0f); + P.uncorrelateCovarianceSetVariance<3>(19, 0.0f); } else { // constrain variances @@ -525,12 +526,6 @@ bool Ekf::checkAndFixCovarianceUpdate(const SquareMatrix24f &KHP) return healthy; } -void Ekf::resetMagRelatedCovariances() -{ - resetQuatCov(); - resetMagCov(); -} - void Ekf::resetQuatCov() { zeroQuatCov(); @@ -542,7 +537,7 @@ void Ekf::resetQuatCov() initialiseQuatCovariances(rot_vec_var); // update the yaw angle variance using the variance of the measurement - if (_params.mag_fusion_type <= MagFuseType::MAG_3D) { + if (_params.mag_fusion_type != MagFuseType::NONE) { // using magnetic heading tuning parameter increaseQuatYawErrVariance(sq(fmaxf(_params.mag_heading_noise, 1.0e-2f))); } @@ -556,31 +551,15 @@ void Ekf::zeroQuatCov() void Ekf::resetMagCov() { - // reset the corresponding rows and columns in the covariance matrix and - // set the variances on the magnetic field states to the measurement variance - clearMagCov(); + if (_mag_decl_cov_reset) { + ECL_INFO("reset mag covariance"); + _mag_decl_cov_reset = false; + } P.uncorrelateCovarianceSetVariance<3>(16, sq(_params.mag_noise)); P.uncorrelateCovarianceSetVariance<3>(19, sq(_params.mag_noise)); - if (!_control_status.flags.mag_3D) { - // save covariance data for re-use when auto-switching between heading and 3-axis fusion - // if already in 3-axis fusion mode, the covariances are automatically saved when switching out - // of this mode - saveMagCovData(); - } -} - -void Ekf::clearMagCov() -{ - zeroMagCov(); - _mag_decl_cov_reset = false; -} - -void Ekf::zeroMagCov() -{ - P.uncorrelateCovarianceSetVariance<3>(16, 0.0f); - P.uncorrelateCovarianceSetVariance<3>(19, 0.0f); + saveMagCovData(); } void Ekf::resetGyroBiasZCov() diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 97ad3117e3..7010626d89 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -45,9 +45,12 @@ bool Ekf::init(uint64_t timestamp) { - bool ret = initialise_interface(timestamp); - reset(); - return ret; + if (!_initialised) { + _initialised = initialise_interface(timestamp); + reset(); + } + + return _initialised; } void Ekf::reset() diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 774bae5fac..0ceb30015b 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -161,9 +161,8 @@ public: if (_control_status.flags.mag_hdg) { heading_innov = _aid_src_mag_heading.innovation; return; - } - if (_control_status.flags.mag_3D) { + } else if (_control_status.flags.mag_3D) { heading_innov = Vector3f(_aid_src_mag.innovation).max(); return; } @@ -188,9 +187,8 @@ public: if (_control_status.flags.mag_hdg) { heading_innov_var = _aid_src_mag_heading.innovation_variance; return; - } - if (_control_status.flags.mag_3D) { + } else if (_control_status.flags.mag_3D) { heading_innov_var = Vector3f(_aid_src_mag.innovation_variance).max(); return; } @@ -215,9 +213,8 @@ public: if (_control_status.flags.mag_hdg) { heading_innov_ratio = _aid_src_mag_heading.test_ratio; return; - } - if (_control_status.flags.mag_3D) { + } else if (_control_status.flags.mag_3D) { heading_innov_ratio = Vector3f(_aid_src_mag.test_ratio).max(); return; } @@ -378,11 +375,11 @@ public: const Vector3f &getMagBias() const { return _state.mag_B; } Vector3f getMagBiasVariance() const { - if (_control_status.flags.mag_3D) { + if (_control_status.flags.mag) { return Vector3f{P(19, 19), P(20, 20), P(21, 21)}; } - return _saved_mag_bf_variance; + return _saved_mag_bf_covmat.diag(); } float getMagBiasLimit() const { return 0.5f; } // 0.5 Gauss @@ -547,6 +544,9 @@ private: bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised + 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) + // booleans true when fresh sensor data is available at the fusion time horizon bool _gps_data_ready{false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused @@ -580,11 +580,10 @@ private: 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 uint64_t _time_yaw_started{0}; ///< last system time in usec that a yaw rotation manoeuvre was detected - uint64_t _mag_use_not_inhibit_us{0}; ///< last system time in usec before magnetometer use was inhibited - - bool _mag_yaw_reset_req{false}; ///< true when a reset of the yaw using the magnetometer data has been requested + float _mag_heading_last_declination{}; ///< last magnetic field declination used for heading fusion (rad) bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event. - bool _synthetic_mag_z_active{false}; ///< true if we are generating synthetic magnetometer Z measurements + uint8_t _nb_mag_heading_reset_available{0}; + uint8_t _nb_mag_3d_reset_available{0}; uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time SquareMatrix24f P{}; ///< state covariance matrix @@ -657,7 +656,6 @@ private: uint8_t _nb_ev_vel_reset_available{0}; uint8_t _nb_ev_yaw_reset_available{0}; #endif // CONFIG_EKF2_EXTERNAL_VISION - bool _inhibit_ev_yaw_use{false}; ///< true when the vision yaw data should not be used (e.g.: NE fusion requires true North) estimator_aid_source1d_s _aid_src_gnss_hgt{}; estimator_aid_source2d_s _aid_src_gnss_pos{}; @@ -706,9 +704,8 @@ private: uint64_t _flt_mag_align_start_time{0}; ///< time that inflight magnetic field alignment started (uSec) uint64_t _time_last_mov_3d_mag_suitable{0}; ///< last system time that sufficient movement to use 3-axis magnetometer fusion was detected (uSec) uint64_t _time_last_mag_check_failing{0}; - Vector3f _saved_mag_bf_variance {}; ///< magnetic field state variances that have been saved for use at the next initialisation (Gauss**2) - Matrix2f _saved_mag_ef_ne_covmat{}; ///< NE magnetic field state covariance sub-matrix saved for use at the next initialisation (Gauss**2) - float _saved_mag_ef_d_variance{}; ///< D magnetic field state variance saved for use at the next initialisation (Gauss**2) + Matrix3f _saved_mag_ef_covmat{}; ///< NED magnetic field state covariance sub-matrix saved for use at the next initialisation (Gauss**2) + Matrix3f _saved_mag_bf_covmat{}; ///< magnetic field state covariance sub-matrix that has been saved for use at the next initialisation (Gauss**2) gps_check_fail_status_u _gps_check_fail_status{}; @@ -765,8 +762,6 @@ private: void updateGpsYaw(const gpsSample &gps_sample); - void startGpsYawFusion(const gpsSample &gps_sample); - #endif // CONFIG_EKF2_GNSS_YAW void stopGpsYawFusion(); @@ -922,14 +917,14 @@ private: } // mag I: states 16, 17, 18 - if (!_control_status.flags.mag_3D) { + if (!_control_status.flags.mag) { K(16) = 0.f; K(17) = 0.f; K(18) = 0.f; } // mag B: states 19, 20, 21 - if (!_control_status.flags.mag_3D) { + if (!_control_status.flags.mag) { K(19) = 0.f; K(20) = 0.f; K(21) = 0.f; @@ -1022,23 +1017,20 @@ private: // control fusion of magnetometer observations void controlMagFusion(); + void controlMagHeadingFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source1d_s &aid_src); + void controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source3d_s &aid_src); - bool resetMagHeading(const Vector3f &mag); - bool resetMagStates(const Vector3f &mag); + bool checkHaglYawResetReq() const; + + void resetMagHeading(const Vector3f &mag); + void resetMagStates(const Vector3f &mag, bool reset_heading = true); bool haglYawResetReq(); - void selectMagAuto(); - void check3DMagFusionSuitability(); void checkYawAngleObservability(); void checkMagBiasObservability(); - bool canUse3DMagFusion() const; - void checkMagDeclRequired(); - bool shouldInhibitMag() const; bool checkMagField(const Vector3f &mag); static bool isMeasuredMatchingExpected(float measured, float expected, float gate); - void runMagAndMagDeclFusions(const Vector3f &mag); - void run3DMagAndDeclFusions(const Vector3f &mag); // control fusion of fake position observations to constrain drift void controlFakePosFusion(); @@ -1069,11 +1061,8 @@ private: void controlBaroHeightFusion(); void controlGnssHeightFusion(const gpsSample &gps_sample); - void stopMagFusion(); - void stopMag3DFusion(); void stopMagHdgFusion(); - void startMagHdgFusion(); - void startMag3DFusion(); + void stopMagFusion(); void stopBaroHgtFusion(); void stopGpsHgtFusion(); @@ -1087,11 +1076,9 @@ private: // do not call before quaternion states are initialised void initialiseQuatCovariances(Vector3f &rot_vec_var); - // perform a limited reset of the magnetic field related state covariances - void resetMagRelatedCovariances(); - void resetQuatCov(); void zeroQuatCov(); + void resetMagCov(); // perform a reset of the wind states and related covariances @@ -1105,8 +1092,6 @@ private: // load and save mag field state covariance data for re-use void loadMagCovData(); void saveMagCovData(); - void clearMagCov(); - void zeroMagCov(); void resetGyroBiasZCov(); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 34e86bf4b5..1c58ee8473 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -1086,33 +1086,24 @@ void Ekf::increaseQuatYawErrVariance(float yaw_variance) P(3,2) -= yaw_variance*SQ[0]*SQ[3]; } -// save covariance data for re-use when auto-switching between heading and 3-axis fusion void Ekf::saveMagCovData() { - // save variances for XYZ body axis field - _saved_mag_bf_variance(0) = P(19, 19); - _saved_mag_bf_variance(1) = P(20, 20); - _saved_mag_bf_variance(2) = P(21, 21); + // save the NED axis covariance sub-matrix + _saved_mag_ef_covmat = P.slice<3, 3>(16, 16); - // save the NE axis covariance sub-matrix - _saved_mag_ef_ne_covmat = P.slice<2, 2>(16, 16); - - // save variance for the D earth axis - _saved_mag_ef_d_variance = P(18, 18); + // save the XYZ body covariance sub-matrix + _saved_mag_bf_covmat = P.slice<3, 3>(19, 19); } void Ekf::loadMagCovData() { - // re-instate variances for the XYZ body axis field - P(19, 19) = _saved_mag_bf_variance(0); - P(20, 20) = _saved_mag_bf_variance(1); - P(21, 21) = _saved_mag_bf_variance(2); + // re-instate the NED axis covariance sub-matrix + P.uncorrelateCovarianceSetVariance<3>(16, 0.f); + P.slice<3, 3>(16, 16) = _saved_mag_ef_covmat; - // re-instate the NE axis covariance sub-matrix - P.slice<2, 2>(16, 16) = _saved_mag_ef_ne_covmat; - - // re-instate the D earth axis variance - P(18, 18) = _saved_mag_ef_d_variance; + // re-instate the XYZ body axis covariance sub-matrix + P.uncorrelateCovarianceSetVariance<3>(19, 0.f); + P.slice<3, 3>(19, 19) = _saved_mag_bf_covmat; } void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) @@ -1133,7 +1124,7 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance) uncorrelateQuatFromOtherStates(); // update the yaw angle variance - if (yaw_variance > FLT_EPSILON) { + if (PX4_ISFINITE(yaw_variance) && (yaw_variance > FLT_EPSILON)) { increaseQuatYawErrVariance(yaw_variance); } @@ -1182,8 +1173,6 @@ bool Ekf::resetYawToEKFGSF() resetQuatStateYaw(_yawEstimator.getYaw(), _yawEstimator.getYawVar()); - // record a magnetic field alignment event to prevent possibility of the EKF trying to reset the yaw to the mag later in flight - _flt_mag_align_start_time = _time_delayed_us; _control_status.flags.yaw_align = true; _information_events.flags.yaw_aligned_to_imu_gps = true; diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index 0955251586..8e780a4f33 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -471,7 +471,7 @@ void EstimatorInterface::setSystemFlagData(const systemFlagUpdate &system_flags) _system_flag_buffer->push(system_flags_new); } else { - ECL_WARN("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _system_flag_buffer->get_newest().time_us, _min_obs_interval_us); + ECL_DEBUG("system flag update too fast %" PRIi64 " < %" PRIu64 " + %d", time_us, _system_flag_buffer->get_newest().time_us, _min_obs_interval_us); } } diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index ed01ca3000..f9c62967c6 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -140,16 +140,34 @@ public: void set_in_air_status(bool in_air) { if (!in_air) { + if (_control_status.flags.in_air) { + ECL_DEBUG("no longer in air"); + } + _time_last_on_ground_us = _time_delayed_us; } else { + if (!_control_status.flags.in_air) { + ECL_DEBUG("in air"); + } + _time_last_in_air = _time_delayed_us; } _control_status.flags.in_air = in_air; } - void set_vehicle_at_rest(bool at_rest) { _control_status.flags.vehicle_at_rest = at_rest; } + void set_vehicle_at_rest(bool at_rest) + { + if (!_control_status.flags.vehicle_at_rest && at_rest) { + ECL_DEBUG("at rest"); + + } else if (_control_status.flags.vehicle_at_rest && !at_rest) { + ECL_DEBUG("no longer at rest"); + } + + _control_status.flags.vehicle_at_rest = at_rest; + } // return true if the attitude is usable bool attitude_valid() const { return _control_status.flags.tilt_align; } @@ -420,9 +438,12 @@ protected: // allocate data buffers and initialize interface variables bool initialise_interface(uint64_t timestamp); + uint64_t _wmm_gps_time_last_checked{0}; // time WMM last checked + uint64_t _wmm_gps_time_last_set{0}; // time WMM last set float _mag_declination_gps{NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad) float _mag_inclination_gps{NAN}; // magnetic inclination returned by the geo library using the last valid GPS position (rad) float _mag_strength_gps{NAN}; // magnetic strength returned by the geo library using the last valid GPS position (T) + float _mag_inclination{NAN}; float _mag_strength{NAN}; diff --git a/src/modules/ekf2/EKF/ev_yaw_control.cpp b/src/modules/ekf2/EKF/ev_yaw_control.cpp index 74faf69abf..4d0472802f 100644 --- a/src/modules/ekf2/EKF/ev_yaw_control.cpp +++ b/src/modules/ekf2/EKF/ev_yaw_control.cpp @@ -49,10 +49,14 @@ void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, const bool common 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); + if (ev_reset) { + _control_status.flags.ev_yaw_fault = false; + } + // determine if we should use EV yaw aiding bool continuing_conditions_passing = (_params.ev_ctrl & static_cast(EvCtrl::YAW)) && _control_status.flags.tilt_align - && !_inhibit_ev_yaw_use + && !_control_status.flags.ev_yaw_fault && PX4_ISFINITE(aid_src.observation) && PX4_ISFINITE(aid_src.observation_variance); diff --git a/src/modules/ekf2/EKF/fake_pos_control.cpp b/src/modules/ekf2/EKF/fake_pos_control.cpp index afe33b5fec..4c876c4597 100644 --- a/src/modules/ekf2/EKF/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/fake_pos_control.cpp @@ -84,6 +84,7 @@ void Ekf::controlFakePosFusion() const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5); if (is_fusion_failing) { + ECL_WARN("fake position fusion failing, resetting"); resetFakePosFusion(); } diff --git a/src/modules/ekf2/EKF/gps_checks.cpp b/src/modules/ekf2/EKF/gps_checks.cpp index 61d8546329..f42ad5599b 100644 --- a/src/modules/ekf2/EKF/gps_checks.cpp +++ b/src/modules/ekf2/EKF/gps_checks.cpp @@ -84,52 +84,53 @@ bool Ekf::collect_gps(const gpsMessage &gps) _NED_origin_initialised = true; - _earth_rate_NED = calcEarthRateNED((float)math::radians(_pos_ref.getProjectionReferenceLat())); - - const bool declination_was_valid = PX4_ISFINITE(_mag_declination_gps); - - // set the magnetic field data returned by the geo library using the current GPS position - _mag_declination_gps = get_mag_declination_radians(lat, lon); - _mag_inclination_gps = get_mag_inclination_radians(lat, lon); - _mag_strength_gps = get_mag_strength_gauss(lat, lon); - - // request a reset of the yaw using the new declination - if ((_params.mag_fusion_type != MagFuseType::NONE) - && !declination_was_valid) { - _mag_yaw_reset_req = true; - } - // save the horizontal and vertical position uncertainty of the origin _gps_origin_eph = gps.eph; _gps_origin_epv = gps.epv; _information_events.flags.gps_checks_passed = true; ECL_INFO("GPS checks passed"); + } - } else if (!_NED_origin_initialised) { - // a rough 2D fix is still sufficient to lookup declination - if ((gps.fix_type >= 2) && (gps.eph < 1000)) { + if (isTimedOut(_wmm_gps_time_last_checked, 1e6)) { + // a rough 2D fix is sufficient to lookup declination + const bool gps_rough_2d_fix = (gps.fix_type >= 2) && (gps.eph < 1000); - const bool declination_was_valid = PX4_ISFINITE(_mag_declination_gps); + if (gps_rough_2d_fix && (_gps_checks_passed || !_NED_origin_initialised)) { // If we have good GPS data set the origin's WGS-84 position to the last gps fix const double lat = gps.lat * 1.0e-7; const double lon = gps.lon * 1.0e-7; // set the magnetic field data returned by the geo library using the current GPS position - _mag_declination_gps = get_mag_declination_radians(lat, lon); - _mag_inclination_gps = get_mag_inclination_radians(lat, lon); - _mag_strength_gps = get_mag_strength_gauss(lat, lon); + const float mag_declination_gps = get_mag_declination_radians(lat, lon); + const float mag_inclination_gps = get_mag_inclination_radians(lat, lon); + const float mag_strength_gps = get_mag_strength_gauss(lat, lon); - // request mag yaw reset if there's a mag declination for the first time - if (_params.mag_fusion_type != MagFuseType::NONE) { - if (!declination_was_valid && PX4_ISFINITE(_mag_declination_gps)) { - _mag_yaw_reset_req = true; + if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { + + const bool mag_declination_changed = (fabsf(mag_declination_gps - _mag_declination_gps) > math::radians(1.f)); + const bool mag_inclination_changed = (fabsf(mag_inclination_gps - _mag_inclination_gps) > math::radians(1.f)); + + if ((_wmm_gps_time_last_set == 0) + || !PX4_ISFINITE(mag_declination_gps) + || !PX4_ISFINITE(mag_inclination_gps) + || !PX4_ISFINITE(mag_strength_gps) + || mag_declination_changed + || mag_inclination_changed + ) { + _mag_declination_gps = mag_declination_gps; + _mag_inclination_gps = mag_inclination_gps; + _mag_strength_gps = mag_strength_gps; + + _wmm_gps_time_last_set = _time_delayed_us; } } _earth_rate_NED = calcEarthRateNED((float)math::radians(lat)); } + + _wmm_gps_time_last_checked = _time_delayed_us; } // start collecting GPS if there is a 3D fix and the NED origin has been set diff --git a/src/modules/ekf2/EKF/gps_control.cpp b/src/modules/ekf2/EKF/gps_control.cpp index 341e041858..c5db7851da 100644 --- a/src/modules/ekf2/EKF/gps_control.cpp +++ b/src/modules/ekf2/EKF/gps_control.cpp @@ -41,7 +41,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) { - if (!_gps_buffer || !((_params.gnss_ctrl & GnssCtrl::HPOS) || (_params.gnss_ctrl & GnssCtrl::VEL))) { + if (!_gps_buffer || (_params.gnss_ctrl == 0)) { stopGpsFusion(); return; } @@ -166,7 +166,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) ECL_WARN("GPS emergency yaw reset"); if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { - // stop using the magnetometer in the main EKF otherwise it' fusion could drag the yaw around + // stop using the magnetometer in the main EKF otherwise its fusion could drag the yaw around // and cause another navigation failure _control_status.flags.mag_fault = true; _warning_events.flags.emergency_yaw_reset_mag_stopped = true; @@ -184,7 +184,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) #if defined(CONFIG_EKF2_EXTERNAL_VISION) if (_control_status.flags.ev_yaw) { - _inhibit_ev_yaw_use = true; + _control_status.flags.ev_yaw_fault = true; } #endif // CONFIG_EKF2_EXTERNAL_VISION @@ -369,11 +369,6 @@ void Ekf::controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passi if (starting_conditions_passing) { // Try to activate GPS yaw fusion if (resetYawToGps(gps_sample.yaw)) { - - stopEvYawFusion(); - stopMagHdgFusion(); - stopMag3DFusion(); - ECL_INFO("starting GPS yaw fusion"); _aid_src_gnss_yaw.time_last_fuse = _time_delayed_us; @@ -429,8 +424,4 @@ void Ekf::stopGpsFusion() stopGpsHgtFusion(); stopGpsYawFusion(); - - // We do not need to know the true North anymore - // EV yaw can start again - _inhibit_ev_yaw_use = false; } diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp new file mode 100644 index 0000000000..541e3454e3 --- /dev/null +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -0,0 +1,218 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mag_3d_control.cpp + * Control functions for ekf mag 3D fusion + */ + +#include "ekf.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); + + const bool wmm_updated = (_wmm_gps_time_last_set > aid_src.time_last_fuse); + + // determine if we should use mag fusion + bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) + && _control_status.flags.tilt_align + && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && (wmm_updated || checkHaglYawResetReq() || isRecent(_time_last_mov_3d_mag_suitable, (uint64_t)3e6)) + && mag_sample.mag.longerThan(0.f) + && mag_sample.mag.isAllFinite(); + + const bool starting_conditions_passing = common_starting_conditions_passing + && continuing_conditions_passing; + + // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise + // before they are used to constrain heading drift + _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) + && _control_status.flags.mag + && _control_status.flags.mag_aligned_in_flight + && !_control_status.flags.mag_fault + && isRecent(aid_src.time_last_fuse, 500'000) + && getMagBiasVariance().longerThan(0.f) && !getMagBiasVariance().longerThan(sq(0.02f)) + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + // TODO: allow clearing mag_fault if mag_3d is good? + + if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) { + ECL_INFO("starting mag 3D fusion"); + + } else if (!_control_status.flags.mag_3D && _control_status_prev.flags.mag_3D) { + ECL_INFO("stopping mag 3D fusion"); + } + + // if we are using 3-axis magnetometer fusion, but without external NE aiding, + // then the declination must be fused as an observation to prevent long term heading drift + // fusing declination when gps aiding is available is optional, but recommended to prevent + // problem if the vehicle is static for extended periods of time + const bool mag_decl_user_selected = (_params.mag_declination_source & GeoDeclinationMask::FUSE_DECL); + const bool not_using_ne_aiding = !_control_status.flags.gps; + _control_status.flags.mag_dec = (_control_status.flags.mag && (not_using_ne_aiding || mag_decl_user_selected)); + + if (_control_status.flags.mag) { + aid_src.timestamp_sample = mag_sample.time_us; + aid_src.fusion_enabled = true; + + if (continuing_conditions_passing && _control_status.flags.yaw_align) { + + if (mag_sample.reset || checkHaglYawResetReq()) { + ECL_INFO("reset to %s", 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; + + } else { + if (!_mag_decl_cov_reset) { + // After any magnetic field covariance reset event the earth field state + // covariances need to be corrected to incorporate knowledge of the declination + // before fusing magnetometer data to prevent rapid rotation of the earth field + // states for the first few observations. + fuseDeclination(0.02f); + _mag_decl_cov_reset = true; + fuseMag(mag_sample.mag, aid_src, false); + + } 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); + + if (_control_status.flags.mag_dec) { + fuseDeclination(0.5f); + } + } + } + + const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); + + if (is_fusion_failing) { + if (_nb_mag_3d_reset_available > 0) { + // 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; + + if (_control_status.flags.in_air) { + _nb_mag_3d_reset_available--; + } + + } else if (starting_conditions_passing) { + // Data seems good, but previous reset did not fix the issue + // something else must be wrong, declare the sensor faulty and stop the fusion + //_control_status.flags.mag_fault = true; + ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); + stopMagFusion(); + + } else { + // A reset did not fix the issue but all the starting checks are not passing + // This could be a temporary issue, stop the fusion without declaring the sensor faulty + ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); + stopMagFusion(); + } + } + + } else { + // Stop fusion but do not declare it faulty + ECL_DEBUG("stopping %s fusion, continuing conditions no longer passing", AID_SRC_NAME); + stopMagFusion(); + } + + } else { + if (starting_conditions_passing) { + + _control_status.flags.mag = true; + + loadMagCovData(); + + // activate fusion, reset mag states and initialize variance if first init or in flight reset + if (!_control_status.flags.yaw_align + || wmm_updated + || !_mag_decl_cov_reset + || !_state.mag_I.longerThan(0.f) + || (P.slice<3, 3>(16, 16).diag().min() < sq(0.0001f)) // mag_I + || (P.slice<3, 3>(19, 19).diag().min() < sq(0.0001f)) // mag_B + ) { + ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME); + + bool reset_heading = !_control_status.flags.yaw_align; + + resetMagStates(_mag_lpf.getState(), reset_heading); + + if (reset_heading) { + _control_status.flags.yaw_align = true; + } + + } else { + ECL_INFO("starting %s fusion", AID_SRC_NAME); + fuseMag(mag_sample.mag, aid_src, false); + } + + aid_src.time_last_fuse = _time_delayed_us; + + _nb_mag_3d_reset_available = 2; + } + } + + aid_src.fusion_enabled = _control_status.flags.mag; +} + +void Ekf::stopMagFusion() +{ + if (_control_status.flags.mag) { + ECL_INFO("stopping mag fusion"); + + _control_status.flags.mag = false; + _control_status.flags.mag_dec = false; + + if (_control_status.flags.mag_3D) { + ECL_INFO("stopping mag 3D fusion"); + _control_status.flags.mag_3D = false; + } + + _fault_status.flags.bad_mag_x = false; + _fault_status.flags.bad_mag_y = false; + _fault_status.flags.bad_mag_z = false; + + _fault_status.flags.bad_mag_decl = false; + + saveMagCovData(); + } +} + diff --git a/src/modules/ekf2/EKF/mag_control.cpp b/src/modules/ekf2/EKF/mag_control.cpp index d1b7907ac2..38599c359e 100644 --- a/src/modules/ekf2/EKF/mag_control.cpp +++ b/src/modules/ekf2/EKF/mag_control.cpp @@ -41,199 +41,86 @@ void Ekf::controlMagFusion() { - bool mag_data_ready = false; - bool mag_data_valid = false; - - magSample mag_sample; - - if (_mag_buffer) { - mag_data_ready = _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample); - - if (mag_data_ready) { - - // sensor or calibration has changed, clear any mag bias and reset low pass filter - if (mag_sample.reset || (_mag_counter == 0)) { - // Zero the magnetometer bias states - _state.mag_B.zero(); - - // Zero the corresponding covariances and set - // variances to the values use for initial alignment - P.uncorrelateCovarianceSetVariance<3>(19, sq(_params.mag_noise)); - - // reset any saved covariance data for re-use when auto-switching between heading and 3-axis fusion - _saved_mag_bf_variance.zero(); - - _control_status.flags.mag_fault = false; - - _mag_lpf.reset(mag_sample.mag); - _mag_counter = 1; - - } else { - _mag_lpf.update(mag_sample.mag); - _mag_counter++; - } - - // if enabled, use knowledge of theoretical magnetic field vector to calculate a synthetic magnetomter Z component value. - // this is useful if there is a lot of interference on the sensor measurement. - if (_params.synthesize_mag_z && (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) - && (_NED_origin_initialised || PX4_ISFINITE(_mag_declination_gps)) - ) { - const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) * Vector3f(_mag_strength_gps, 0, 0); - mag_sample.mag(2) = calculate_synthetic_mag_z_measurement(mag_sample.mag, mag_earth_pred); - _control_status.flags.synthetic_mag_z = true; - - } else { - _control_status.flags.synthetic_mag_z = false; - } - - mag_data_valid = checkMagField(mag_sample.mag); - - // compute mag heading innovation (for estimator_aid_src_mag_heading logging) - const Vector3f mag_observation = mag_sample.mag - _state.mag_B; - const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); - const Vector3f mag_earth_pred = R_to_earth * mag_observation; - - resetEstimatorAidStatus(_aid_src_mag_heading); - _aid_src_mag_heading.timestamp_sample = mag_sample.time_us; - _aid_src_mag_heading.observation = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination(); - _aid_src_mag_heading.innovation = wrap_pi(getEulerYaw(_R_to_earth) - _aid_src_mag_heading.observation); - - // compute magnetometer innovations (for estimator_aid_src_mag logging) - // rotate magnetometer earth field state into body frame - const Vector3f mag_I_body = _state.quat_nominal.rotateVectorInverse(_state.mag_I); - const Vector3f mag_innov = mag_I_body - mag_observation; - - resetEstimatorAidStatus(_aid_src_mag); - _aid_src_mag.timestamp_sample = mag_sample.time_us; - mag_observation.copyTo(_aid_src_mag.observation); - mag_innov.copyTo(_aid_src_mag.innovation); - - } else if (!isNewestSampleRecent(_time_last_mag_buffer_push, 2 * MAG_MAX_INTERVAL)) { - // No data anymore. Stop until it comes back. - stopMagFusion(); - } - } - - // If we are on ground, reset the flight alignment flag so that the mag fields will be - // re-initialised next time we achieve flight altitude - if (!_control_status.flags.in_air) { + // reset the flight alignment flag so that the mag fields will be + // re-initialised next time we achieve flight altitude + if (!_control_status_prev.flags.in_air && _control_status.flags.in_air) { _control_status.flags.mag_aligned_in_flight = false; } - if (mag_data_ready && mag_data_valid && !_control_status.flags.tilt_align && !_control_status.flags.yaw_align) { - // calculate the initial magnetic field and yaw alignment - // but do not mark the yaw alignement complete as it needs to be - // reset once the leveling phase is done - if (_params.mag_fusion_type <= MagFuseType::MAG_3D) { - if ((_mag_counter > 1) && isTimedOut(_aid_src_mag_heading.time_last_fuse, (uint64_t)100'000)) { - // rotate the magnetometer measurements into earth frame using a zero yaw angle - // the angle of the projection onto the horizontal gives the yaw angle - const Vector3f mag_earth_pred = updateYawInRotMat(0.f, _R_to_earth) * _mag_lpf.getState(); - const float yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination(); + // check mag state observability + checkYawAngleObservability(); + checkMagBiasObservability(); - const float yaw_prev = getEulerYaw(_R_to_earth); - - if (fabsf(yaw_new - yaw_prev) > math::radians(1.f)) { - - ECL_INFO("mag heading init %.3f -> %.3f rad (declination %.1f)", (double)yaw_prev, (double)yaw_new, (double)getMagDeclination()); - - // update the rotation matrix using the new yaw value - _R_to_earth = updateYawInRotMat(yaw_new, Dcmf(_state.quat_nominal)); - _state.quat_nominal = _R_to_earth; - - // reset the output predictor state history to match the EKF initial values - _output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _state.pos); - - // set the earth magnetic field states using the updated rotation - _state.mag_I = _R_to_earth * _mag_lpf.getState(); - _state.mag_B.zero(); - - _aid_src_mag_heading.time_last_fuse = _time_delayed_us; - _time_last_heading_fuse = _time_delayed_us; - } - } - } - - return; + if (_mag_bias_observable || _yaw_angle_observable) { + _time_last_mov_3d_mag_suitable = _time_delayed_us; } - if (_params.mag_fusion_type >= MagFuseType::NONE - || _control_status.flags.mag_fault - || !_control_status.flags.tilt_align) { - + if (_params.mag_fusion_type == MagFuseType::NONE) { stopMagFusion(); + stopMagHdgFusion(); return; } - _mag_yaw_reset_req |= !_control_status.flags.yaw_align; + // stop mag (require a reset before using again) if there was an external yaw reset (yaw estimator, GPS yaw, etc) + if (_mag_decl_cov_reset && (_state_reset_status.reset_count.quat != _state_reset_count_prev.quat)) { + ECL_INFO("yaw reset, stopping mag fusion to force reinitialization"); + stopMagFusion(); + resetMagCov(); + } - if (mag_data_ready && !_control_status.flags.ev_yaw && !_control_status.flags.gps_yaw) { + magSample mag_sample; - if (shouldInhibitMag() || !mag_data_valid) { - if (uint32_t(_time_delayed_us - _mag_use_not_inhibit_us) > (uint32_t)5e6) { - // If magnetometer use has been inhibited continuously then stop the fusion - stopMagFusion(); - } + if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { - return; + if (mag_sample.reset || (_mag_counter == 0)) { + // sensor or calibration has changed, reset low pass filter (reset handled by controlMag3DFusion/controlMagHeadingFusion) + _control_status.flags.mag_fault = false; + + _state.mag_B.zero(); + resetMagCov(); + + _mag_lpf.reset(mag_sample.mag); + _mag_counter = 1; } else { - _mag_use_not_inhibit_us = _time_delayed_us; + _mag_lpf.update(mag_sample.mag); + _mag_counter++; } - const bool mag_enabled_previously = _control_status.flags.mag_hdg || _control_status.flags.mag_3D; + const bool starting_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) + && checkMagField(mag_sample.mag) + && (_mag_counter > 5) // wait until we have more than a few samples through the filter + && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame + && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset + && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); - // Determine if we should use simple magnetic heading fusion which works better when - // there are large external disturbances or the more accurate 3-axis fusion - switch (_params.mag_fusion_type) { - default: - // FALLTHROUGH - case MagFuseType::AUTO: - selectMagAuto(); - break; + // if enabled, use knowledge of theoretical magnetic field vector to calculate a synthetic magnetomter Z component value. + // this is useful if there is a lot of interference on the sensor measurement. + if (_params.synthesize_mag_z && (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) + && (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) + ) { + const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) + * Vector3f(_mag_strength_gps, 0, 0); - case MagFuseType::INDOOR: + mag_sample.mag(2) = calculate_synthetic_mag_z_measurement(mag_sample.mag, mag_earth_pred); - /* fallthrough */ - case MagFuseType::HEADING: - startMagHdgFusion(); - break; + _control_status.flags.synthetic_mag_z = true; - case MagFuseType::MAG_3D: - startMag3DFusion(); - break; + } else { + _control_status.flags.synthetic_mag_z = false; } - if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { + controlMag3DFusion(mag_sample, starting_conditions_passing, _aid_src_mag); + controlMagHeadingFusion(mag_sample, starting_conditions_passing, _aid_src_mag_heading); - if (_mag_yaw_reset_req || !_control_status.flags.yaw_align || mag_sample.reset || !mag_enabled_previously || haglYawResetReq()) { - - if ((_mag_counter > 1) && resetMagStates(_mag_lpf.getState())) { - _mag_yaw_reset_req = false; - - } else { - // mag reset failed, try again next time - _mag_yaw_reset_req = true; - - if (mag_sample.reset) { - return; - } - } - } - } - - if (!_control_status.flags.yaw_align) { - // Having the yaw aligned is mandatory to continue - return; - } - - checkMagDeclRequired(); - - runMagAndMagDeclFusions(mag_sample.mag); + } else if (!isNewestSampleRecent(_time_last_mag_buffer_push, 2 * MAG_MAX_INTERVAL)) { + // No data anymore. Stop until it comes back. + stopMagHdgFusion(); + stopMagFusion(); } } -bool Ekf::haglYawResetReq() +bool Ekf::checkHaglYawResetReq() const { // We need to reset the yaw angle after climbing away from the ground to enable // recovery from ground level magnetic interference. @@ -244,30 +131,20 @@ bool Ekf::haglYawResetReq() static constexpr float mag_anomalies_max_hagl = 1.5f; const bool above_mag_anomalies = (getTerrainVPos() - _state.pos(2)) > mag_anomalies_max_hagl; return above_mag_anomalies; -#else - return true; #endif // CONFIG_EKF2_RANGE_FINDER } return false; } -bool Ekf::resetMagStates(const Vector3f &mag) +void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) { - // prevent a reset being performed more than once on the same frame - if ((_flt_mag_align_start_time == _time_delayed_us) - || (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align)) { - return false; - } - - bool reset_heading = true; - bool has_realigned_yaw = false; - // reinit mag states const Vector3f mag_I_before_reset = _state.mag_I; const Vector3f mag_B_before_reset = _state.mag_B; - const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); + // reset covariances to default + resetMagCov(); // if world magnetic model (inclination, declination, strength) available then use it to reset mag states if (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) { @@ -276,91 +153,72 @@ bool Ekf::resetMagStates(const Vector3f &mag) const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) * Vector3f(_mag_strength_gps, 0, 0); + // mag_B: reset if (isYawEmergencyEstimateAvailable()) { const Dcmf R_to_earth = updateYawInRotMat(_yawEstimator.getYaw(), _R_to_earth); const Dcmf R_to_body = R_to_earth.transpose(); - // mag_B: reset using WMM and yaw estimator, initialize variances (so resetMagHeading will use mag bias) + // mag_B: reset using WMM and yaw estimator _state.mag_B = mag - (R_to_body * mag_earth_pred); - P.uncorrelateCovarianceSetVariance<3>(19, R_MAG); - _saved_mag_bf_variance = P.slice<3, 3>(19, 19).diag(); - ECL_INFO("using yaw estimator to reset mag bias [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", - (double)mag_B_before_reset(0), (double)mag_B_before_reset(1), (double)mag_B_before_reset(2), - (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) - ); + ECL_INFO("resetMagStates using yaw estimator"); + + } else if (!reset_heading && _control_status.flags.yaw_align) { + // mag_B: reset using WMM + const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); + _state.mag_B = mag - (R_to_body * mag_earth_pred); } else { - // mag_B: reset _state.mag_B.zero(); } + // mag_I: reset, skipped if no change in state and variance good + _state.mag_I = mag_earth_pred; + if (reset_heading) { - has_realigned_yaw = resetMagHeading(mag); + resetMagHeading(mag); } - // mag_I: reset to WMM - _state.mag_I = mag_earth_pred; + // earth field was reset to WMM, skip initial declination fusion + _mag_decl_cov_reset = true; } else { // mag_B: reset _state.mag_B.zero(); + // Use the magnetometer measurement to reset the field states if (reset_heading) { - has_realigned_yaw = resetMagHeading(mag); + resetMagHeading(mag); } // mag_I: use the last magnetometer measurements to reset the field states _state.mag_I = _R_to_earth * mag; } - resetMagCov(); + if (!mag_I_before_reset.longerThan(0.f)) { + ECL_INFO("initializing mag I [%.3f, %.3f, %.3f], mag B [%.3f, %.3f, %.3f]", + (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), + (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) + ); - if (has_realigned_yaw) { - if (!mag_I_before_reset.longerThan(0.f)) { - ECL_INFO("initializing mag I [%.3f, %.3f, %.3f], mag B [%.3f, %.3f, %.3f]", - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), + } else { + ECL_INFO("resetting mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", + (double)mag_I_before_reset(0), (double)mag_I_before_reset(1), (double)mag_I_before_reset(2), + (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2) + ); + + if (mag_B_before_reset.longerThan(0.f) || _state.mag_B.longerThan(0.f)) { + ECL_INFO("resetting mag B [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", + (double)mag_B_before_reset(0), (double)mag_B_before_reset(1), (double)mag_B_before_reset(2), (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) ); - - } else { - ECL_INFO("resetting mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", - (double)mag_I_before_reset(0), (double)mag_I_before_reset(1), (double)mag_I_before_reset(2), - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2) - ); } - - _control_status.flags.yaw_align = true; - - if (_control_status.flags.in_air) { - // record the start time for the magnetic field alignment - _flt_mag_align_start_time = _time_delayed_us; - _control_status.flags.mag_aligned_in_flight = true; - - } else { - _flt_mag_align_start_time = 0; - _control_status.flags.mag_aligned_in_flight = false; - } - - return true; } - return false; -} - -void Ekf::selectMagAuto() -{ - check3DMagFusionSuitability(); - canUse3DMagFusion() ? startMag3DFusion() : startMagHdgFusion(); -} - -void Ekf::check3DMagFusionSuitability() -{ - checkYawAngleObservability(); - checkMagBiasObservability(); - - if (_mag_bias_observable || _yaw_angle_observable) { - _time_last_mov_3d_mag_suitable = _time_delayed_us; + // record the start time for the magnetic field alignment + if (_control_status.flags.in_air) { + _control_status.flags.mag_aligned_in_flight = true; + _flt_mag_align_start_time = _time_delayed_us; } } @@ -399,49 +257,10 @@ void Ekf::checkMagBiasObservability() _time_yaw_started = _time_delayed_us; } -bool Ekf::canUse3DMagFusion() const -{ - // Use of 3D fusion requires an in-air heading alignment but it should not - // be used when the heading and mag biases are not observable for more than 2 seconds - return _control_status.flags.mag_aligned_in_flight - && ((_time_delayed_us - _time_last_mov_3d_mag_suitable) < (uint64_t)2e6); -} - -void Ekf::checkMagDeclRequired() -{ - // if we are using 3-axis magnetometer fusion, but without external NE aiding, - // then the declination must be fused as an observation to prevent long term heading drift - // fusing declination when gps aiding is available is optional, but recommended to prevent - // problem if the vehicle is static for extended periods of time - const bool user_selected = (_params.mag_declination_source & GeoDeclinationMask::FUSE_DECL); - const bool not_using_ne_aiding = !_control_status.flags.gps; - _control_status.flags.mag_dec = (_control_status.flags.mag_3D && (not_using_ne_aiding || user_selected)); -} - -bool Ekf::shouldInhibitMag() const -{ - // If the user has selected auto protection against indoor magnetic field errors, only use the magnetometer - // if a yaw angle relative to true North is required for navigation. If no GPS or other earth frame aiding - // is available, assume that we are operating indoors and the magnetometer should not be used. - // Also inhibit mag fusion when a strong magnetic field interference is detected or the user - // has explicitly stopped magnetometer use. - const bool user_selected = (_params.mag_fusion_type == MagFuseType::INDOOR); - - const bool heading_not_required_for_navigation = !_control_status.flags.gps; - - return (user_selected && heading_not_required_for_navigation) || _control_status.flags.mag_field_disturbed; -} - bool Ekf::checkMagField(const Vector3f &mag_sample) { _control_status.flags.mag_field_disturbed = false; - if ((_params.mag_fusion_type == MagFuseType::NONE) - || (_params.mag_fusion_type == MagFuseType::INDOOR && !_control_status.flags.gps)) { - //TODO: review this: gps flag cannnot be set if yaw isn't aligned - return false; - } - if (_params.mag_check == 0) { // skip all checks return true; @@ -506,105 +325,38 @@ bool Ekf::isMeasuredMatchingExpected(const float measured, const float expected, && (measured <= expected + gate); } -void Ekf::runMagAndMagDeclFusions(const Vector3f &mag) +void Ekf::resetMagHeading(const Vector3f &mag) { - if (_control_status.flags.mag_3D) { - run3DMagAndDeclFusions(mag); - - } else if (_control_status.flags.mag_hdg) { - // Rotate the measurements into earth frame using the zero yaw angle - Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); - - Vector3f mag_earth_pred = R_to_earth * (mag - _state.mag_B); - - // the angle of the projection onto the horizontal gives the yaw angle - // calculate the yaw innovation and wrap to the interval between +-pi - float measured_hdg = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination(); - - float innovation = wrap_pi(getEulerYaw(_R_to_earth) - measured_hdg); - float obs_var = fmaxf(sq(_params.mag_heading_noise), 1.e-4f); - - _aid_src_mag_heading.observation = measured_hdg; - _aid_src_mag_heading.observation_variance = obs_var; - _aid_src_mag_heading.innovation = innovation; - _aid_src_mag_heading.fusion_enabled = _control_status.flags.mag_hdg; - - fuseYaw(_aid_src_mag_heading); - } -} - -void Ekf::run3DMagAndDeclFusions(const Vector3f &mag) -{ - // sanity check mag_B before they are used to constrain heading drift - const Vector3f mag_bias_var = P.slice<3, 3>(19, 19).diag(); - const bool mag_bias_var_good = (mag_bias_var.min() > 0.f) && (mag_bias_var.max() < sq(0.02f)); - - const bool update_all_states = _control_status.flags.mag_aligned_in_flight && mag_bias_var_good; - - if (!_mag_decl_cov_reset) { - // After any magnetic field covariance reset event the earth field state - // covariances need to be corrected to incorporate knowledge of the declination - // before fusing magnetometer data to prevent rapid rotation of the earth field - // states for the first few observations. - fuseDeclination(0.02f); - _mag_decl_cov_reset = true; - fuseMag(mag, _aid_src_mag, update_all_states); - - } 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. - fuseMag(mag, _aid_src_mag, update_all_states); - - if (_control_status.flags.mag_dec) { - fuseDeclination(0.5f); - } - } -} - -bool Ekf::resetMagHeading(const Vector3f &mag) -{ - // prevent a reset being performed more than once on the same frame - if ((_flt_mag_align_start_time == _time_delayed_us) || (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align)) { - return false; - } - // use mag bias if variance good (unless configured for HEADING only) Vector3f mag_bias{0.f, 0.f, 0.f}; const Vector3f mag_bias_var = getMagBiasVariance(); - if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= math::max(sq(_params.mag_noise), sq(0.01f)))) { + if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= sq(_params.mag_noise))) { mag_bias = _state.mag_B; } - const Vector3f mag_init = _mag_lpf.getState() - mag_bias; + // calculate mag heading + // rotate the magnetometer measurements into earth frame using a zero yaw angle + const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); - const bool heading_required_for_navigation = _control_status.flags.gps; + // the angle of the projection onto the horizontal gives the yaw angle + const Vector3f mag_earth_pred = R_to_earth * (mag - mag_bias); - if ((_params.mag_fusion_type <= MagFuseType::MAG_3D) || ((_params.mag_fusion_type == MagFuseType::INDOOR) && heading_required_for_navigation)) { + // calculate the observed yaw angle and yaw variance + const float declination = getMagDeclination(); + float yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + declination; + float yaw_new_variance = math::max(sq(_params.mag_heading_noise), sq(0.01f)); - // rotate the magnetometer measurements into earth frame using a zero yaw angle - const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); + ECL_INFO("reset mag heading %.3f -> %.3f rad (bias:[%.3f, %.3f, %.3f], declination:%.1f)", + (double)getEulerYaw(_R_to_earth), (double)yaw_new, + (double)mag_bias(0), (double)mag_bias(1), (double)mag_bias(2), + (double)declination); - // the angle of the projection onto the horizontal gives the yaw angle - const Vector3f mag_earth_pred = R_to_earth * mag_init; + // update quaternion states and corresponding covarainces + resetQuatStateYaw(yaw_new, yaw_new_variance); + _mag_heading_last_declination = declination; - // calculate the observed yaw angle and yaw variance - float yaw_new = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination(); - float yaw_new_variance = math::max(sq(_params.mag_heading_noise), sq(0.01f)); - - ECL_INFO("reset mag heading %.3f -> %.3f rad (bias:[%.3f, %.3f, %.3f], declination:%.1f)", - (double)getEulerYaw(_R_to_earth), (double)yaw_new, - (double)mag_bias(0), (double)mag_bias(1), (double)mag_bias(2), - (double)getMagDeclination()); - - // update quaternion states and corresponding covarainces - resetQuatStateYaw(yaw_new, yaw_new_variance); - - return true; - } - - return false; + _time_last_heading_fuse = _time_delayed_us; } float Ekf::getMagDeclination() @@ -616,72 +368,12 @@ float Ekf::getMagDeclination() } else if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) { // use parameter value until GPS is available, then use value returned by geo library - if (_NED_origin_initialised || PX4_ISFINITE(_mag_declination_gps)) { + if (PX4_ISFINITE(_mag_declination_gps)) { return _mag_declination_gps; - - } else { - return math::radians(_params.mag_declination_deg); } - - } else { - // always use the parameter value - return math::radians(_params.mag_declination_deg); } + + // otherwise use the parameter value + return math::radians(_params.mag_declination_deg); } -void Ekf::stopMagFusion() -{ - if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) { - ECL_INFO("stopping all mag fusion"); - stopMag3DFusion(); - stopMagHdgFusion(); - clearMagCov(); - } -} - -void Ekf::stopMag3DFusion() -{ - // save covariance data for re-use if currently doing 3-axis fusion - if (_control_status.flags.mag_3D) { - saveMagCovData(); - - _control_status.flags.mag_3D = false; - _control_status.flags.mag_dec = false; - - _fault_status.flags.bad_mag_x = false; - _fault_status.flags.bad_mag_y = false; - _fault_status.flags.bad_mag_z = false; - - _fault_status.flags.bad_mag_decl = false; - } -} - -void Ekf::stopMagHdgFusion() -{ - if (_control_status.flags.mag_hdg) { - _control_status.flags.mag_hdg = false; - - _fault_status.flags.bad_hdg = false; - } -} - -void Ekf::startMagHdgFusion() -{ - if (!_control_status.flags.mag_hdg) { - stopMag3DFusion(); - ECL_INFO("starting mag heading fusion"); - _control_status.flags.mag_hdg = true; - } -} - -void Ekf::startMag3DFusion() -{ - if (!_control_status.flags.mag_3D) { - - stopMagHdgFusion(); - - zeroMagCov(); - loadMagCovData(); - _control_status.flags.mag_3D = true; - } -} diff --git a/src/modules/ekf2/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/mag_fusion.cpp index 0fc53b7190..f04a2df8e8 100644 --- a/src/modules/ekf2/EKF/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/mag_fusion.cpp @@ -54,10 +54,10 @@ bool Ekf::fuseMag(const Vector3f &mag, 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 = sq(fmaxf(_params.mag_noise, 0.0f)); + 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 char* numerical_error_covariance_reset_string = "numerical error - covariance reset"; + const char *numerical_error_covariance_reset_string = "numerical error - covariance reset"; Vector3f mag_innov; Vector3f innov_var; @@ -75,7 +75,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo _fault_status.flags.bad_mag_x = true; // we need to re-initialise covariances and abort this fusion step - resetMagRelatedCovariances(); + if (update_all_states) { + resetQuatCov(); + } + + resetMagCov(); + ECL_ERR("magX %s", numerical_error_covariance_reset_string); return false; } @@ -88,7 +93,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo _fault_status.flags.bad_mag_y = true; // we need to re-initialise covariances and abort this fusion step - resetMagRelatedCovariances(); + if (update_all_states) { + resetQuatCov(); + } + + resetMagCov(); + ECL_ERR("magY %s", numerical_error_covariance_reset_string); return false; } @@ -100,7 +110,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo _fault_status.flags.bad_mag_z = true; // we need to re-initialise covariances and abort this fusion step - resetMagRelatedCovariances(); + if (update_all_states) { + resetQuatCov(); + } + + resetMagCov(); + ECL_ERR("magZ %s", numerical_error_covariance_reset_string); return false; } @@ -118,7 +133,7 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo aid_src_mag.innovation[i] = mag_innov(i); } - aid_src_mag.fusion_enabled = _control_status.flags.mag_3D && update_all_states; + aid_src_mag.fusion_enabled = _control_status.flags.mag; // do not use the synthesized measurement for the magnetomter Z component for 3D fusion if (_control_status.flags.synthetic_mag_z) { @@ -159,7 +174,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo _fault_status.flags.bad_mag_y = true; // we need to re-initialise covariances and abort this fusion step - resetMagRelatedCovariances(); + if (update_all_states) { + resetQuatCov(); + } + + resetMagCov(); + ECL_ERR("magY %s", numerical_error_covariance_reset_string); return false; } @@ -183,7 +203,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo _fault_status.flags.bad_mag_z = true; // we need to re-initialise covariances and abort this fusion step - resetMagRelatedCovariances(); + if (update_all_states) { + resetQuatCov(); + } + + resetMagCov(); + ECL_ERR("magZ %s", numerical_error_covariance_reset_string); return false; } @@ -214,7 +239,7 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo _fault_status.flags.bad_mag_y = !fused[1]; _fault_status.flags.bad_mag_z = !fused[2]; - if (fused[0] && fused[1] && fused[2]) { + if (fused[0] && fused[1] && (fused[2] || _control_status.flags.synthetic_mag_z)) { aid_src_mag.fused = true; aid_src_mag.time_last_fuse = _time_delayed_us; @@ -230,7 +255,7 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } // update quaternion states and covariances using the yaw innovation and yaw observation variance -bool Ekf::fuseYaw(estimator_aid_source1d_s& aid_src_status) +bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status) { Vector24f H_YAW; computeYawInnovVarAndH(aid_src_status.observation_variance, aid_src_status.innovation_variance, H_YAW); @@ -238,7 +263,7 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s& aid_src_status) return fuseYaw(aid_src_status, H_YAW); } -bool Ekf::fuseYaw(estimator_aid_source1d_s& aid_src_status, const Vector24f &H_YAW) +bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const Vector24f &H_YAW) { // define the innovation gate size float gate_sigma = math::max(_params.heading_innov_gate, 1.f); @@ -285,9 +310,9 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s& aid_src_status, const Vector24f &H_Y // 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 @@ -339,6 +364,10 @@ void Ekf::computeYawInnovVarAndH(float variance, float &innovation_variance, Vec bool Ekf::fuseDeclination(float decl_sigma) { + if (!_control_status.flags.mag) { + return false; + } + // observation variance (rad**2) const float R_DECL = sq(decl_sigma); @@ -346,6 +375,7 @@ bool Ekf::fuseDeclination(float decl_sigma) float decl_pred; float innovation_variance; + // TODO: review getMagDeclination() usage, use mag_I, _mag_declination_gps, or parameter? sym::ComputeMagDeclinationPredInnovVarAndH(getStateAtFusionHorizonAsVector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance, &H); const float innovation = wrap_pi(decl_pred - getMagDeclination()); @@ -373,26 +403,29 @@ bool Ekf::fuseDeclination(float decl_sigma) void Ekf::limitDeclination() { + const Vector3f mag_I_before = _state.mag_I; + // get a reference value for the earth field declinaton and minimum plausible horizontal field strength - // set to 50% of the horizontal strength from geo tables if location is known - float decl_reference; + float decl_reference = NAN; float h_field_min = 0.001f; - if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) { - // use parameter value until GPS is available, then use value returned by geo library - if (_NED_origin_initialised || PX4_ISFINITE(_mag_declination_gps)) { - decl_reference = _mag_declination_gps; - h_field_min = fmaxf(h_field_min, 0.5f * _mag_strength_gps * cosf(_mag_inclination_gps)); + if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL + && (PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps) && PX4_ISFINITE(_mag_inclination_gps)) + ) { + decl_reference = _mag_declination_gps; - } else { - decl_reference = math::radians(_params.mag_declination_deg); - } + // set to 50% of the horizontal strength from geo tables if location is known + h_field_min = fmaxf(h_field_min, 0.5f * _mag_strength_gps * cosf(_mag_inclination_gps)); - } else { - // always use the parameter value + } else if (_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) { + // use parameter value if GPS isn't available decl_reference = math::radians(_params.mag_declination_deg); } + if (!PX4_ISFINITE(decl_reference)) { + return; + } + // do not allow the horizontal field length to collapse - this will make the declination fusion badly conditioned // and can result in a reversal of the NE field states which the filter cannot recover from // apply a circular limit @@ -406,9 +439,8 @@ void Ekf::limitDeclination() } else { // too small to scale radially so set to expected value - const float mag_declination = getMagDeclination(); - _state.mag_I(0) = 2.0f * h_field_min * cosf(mag_declination); - _state.mag_I(1) = 2.0f * h_field_min * sinf(mag_declination); + _state.mag_I(0) = 2.0f * h_field_min * cosf(decl_reference); + _state.mag_I(1) = 2.0f * h_field_min * sinf(decl_reference); } h_field = h_field_min; @@ -428,6 +460,14 @@ void Ekf::limitDeclination() _state.mag_I(0) = h_field * cosf(decl_min); _state.mag_I(1) = h_field * sinf(decl_min); } + + if ((mag_I_before - _state.mag_I).longerThan(0.01f)) { + ECL_DEBUG("declination limited mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f] (decl: %.3f)", + (double)mag_I_before(0), (double)mag_I_before(1), (double)mag_I_before(2), + (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), + (double)decl_reference + ); + } } float Ekf::calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted) diff --git a/src/modules/ekf2/EKF/mag_heading_control.cpp b/src/modules/ekf2/EKF/mag_heading_control.cpp new file mode 100644 index 0000000000..9c00d01312 --- /dev/null +++ b/src/modules/ekf2/EKF/mag_heading_control.cpp @@ -0,0 +1,190 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mag_heading_control.cpp + * Control functions for ekf mag heading fusion + */ + +#include "ekf.h" + +void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, + estimator_aid_source1d_s &aid_src) +{ + static constexpr const char *AID_SRC_NAME = "mag heading"; + + // use mag bias if variance good + Vector3f mag_bias{0.f, 0.f, 0.f}; + const Vector3f mag_bias_var = getMagBiasVariance(); + + if ((mag_bias_var.min() > 0.f) && (mag_bias_var.max() <= sq(_params.mag_noise))) { + mag_bias = _state.mag_B; + } + + // calculate mag heading + // Rotate the measurements into earth frame using the zero yaw angle + const Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth); + + // the angle of the projection onto the horizontal gives the yaw angle + // calculate the yaw innovation and wrap to the interval between +-pi + const Vector3f mag_earth_pred = R_to_earth * (mag_sample.mag - mag_bias); + 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)); + + if (_control_status.flags.yaw_align) { + // mag heading + aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation); + + } 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)); + } + + // determine if we should use mag heading aiding + bool continuing_conditions_passing = ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) + && _control_status.flags.tilt_align + && (_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 + && !_control_status.flags.gps_yaw + && PX4_ISFINITE(aid_src.observation) + && PX4_ISFINITE(aid_src.observation_variance); + + const bool starting_conditions_passing = common_starting_conditions_passing + && continuing_conditions_passing + && isTimedOut(aid_src.time_last_fuse, 3e6); + + if (_control_status.flags.mag_hdg) { + aid_src.fusion_enabled = true; + aid_src.timestamp_sample = mag_sample.time_us; + + if (continuing_conditions_passing && _control_status.flags.yaw_align) { + + const bool declination_changed = _control_status_prev.flags.mag_hdg + && (fabsf(declination - _mag_heading_last_declination) > math::radians(3.f)); + + if (mag_sample.reset || declination_changed) { + if (declination_changed) { + ECL_INFO("reset to %s, declination changed %.5f->%.5f", + AID_SRC_NAME, (double)_mag_heading_last_declination, (double)declination); + + } else { + ECL_INFO("reset to %s", AID_SRC_NAME); + } + + resetMagHeading(_mag_lpf.getState()); + aid_src.time_last_fuse = _time_delayed_us; + + } else { + fuseYaw(aid_src); + } + + const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); + + if (is_fusion_failing) { + if (_nb_mag_heading_reset_available > 0) { + // Data seems good, attempt a reset + ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); + resetMagHeading(_mag_lpf.getState()); + aid_src.time_last_fuse = _time_delayed_us; + + if (_control_status.flags.in_air) { + _nb_mag_heading_reset_available--; + } + + } else if (starting_conditions_passing) { + // Data seems good, but previous reset did not fix the issue + // something else must be wrong, declare the sensor faulty and stop the fusion + _control_status.flags.mag_fault = true; + ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); + stopMagHdgFusion(); + + } else { + // A reset did not fix the issue but all the starting checks are not passing + // This could be a temporary issue, stop the fusion without declaring the sensor faulty + ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); + stopMagHdgFusion(); + } + } + + } else { + // Stop fusion but do not declare it faulty + ECL_WARN("stopping %s fusion, continuing conditions failing", AID_SRC_NAME); + stopMagHdgFusion(); + } + + } else { + if (starting_conditions_passing) { + // activate fusion + ECL_INFO("starting %s fusion", AID_SRC_NAME); + + if (!_control_status.flags.yaw_align) { + // reset heading + resetMagHeading(_mag_lpf.getState()); + _control_status.flags.yaw_align = true; + } + + _control_status.flags.mag_hdg = true; + aid_src.time_last_fuse = _time_delayed_us; + + _nb_mag_heading_reset_available = 1; + } + } + + aid_src.fusion_enabled = _control_status.flags.mag_hdg; + + // 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(); +} + +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; + + _fault_status.flags.bad_hdg = false; + } +} diff --git a/src/modules/ekf2/EKF/zero_innovation_heading_update.cpp b/src/modules/ekf2/EKF/zero_innovation_heading_update.cpp index cfc48a14a9..16cc545819 100644 --- a/src/modules/ekf2/EKF/zero_innovation_heading_update.cpp +++ b/src/modules/ekf2/EKF/zero_innovation_heading_update.cpp @@ -44,13 +44,12 @@ void Ekf::controlZeroInnovationHeadingUpdate() || _control_status.flags.ev_yaw || _control_status.flags.gps_yaw; // fuse zero innovation at a limited rate if the yaw variance is too large - if (_control_status.flags.tilt_align - && !yaw_aiding + if(!yaw_aiding && isTimedOut(_time_last_heading_fuse, (uint64_t)200'000)) { // Use an observation variance larger than usual but small enough // to constrain the yaw variance just below the threshold - const float obs_var = 0.25f; + const float obs_var = _control_status.flags.tilt_align ? 0.25f : 0.001f; estimator_aid_source1d_s aid_src_status{}; aid_src_status.observation = getEulerYaw(_state.quat_nominal); @@ -61,7 +60,7 @@ void Ekf::controlZeroInnovationHeadingUpdate() computeYawInnovVarAndH(obs_var, aid_src_status.innovation_variance, H_YAW); - if ((aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) { + if (!_control_status.flags.tilt_align || (aid_src_status.innovation_variance - obs_var) > sq(_params.mag_heading_noise)) { // The yaw variance is too large, fuse fake measurement aid_src_status.fusion_enabled = true; fuseYaw(aid_src_status, H_YAW); diff --git a/src/modules/ekf2/EKF/zero_velocity_update.cpp b/src/modules/ekf2/EKF/zero_velocity_update.cpp index 0897262ea3..4863918a13 100644 --- a/src/modules/ekf2/EKF/zero_velocity_update.cpp +++ b/src/modules/ekf2/EKF/zero_velocity_update.cpp @@ -46,7 +46,7 @@ void Ekf::controlZeroVelocityUpdate() if (zero_velocity_update_data_ready) { const bool continuing_conditions_passing = _control_status.flags.vehicle_at_rest && _control_status_prev.flags.vehicle_at_rest - && !isVerticalVelocityAidingActive(); // otherwise the filter is "too rigid" to follow a position drift + && (!isVerticalVelocityAidingActive() || !_control_status.flags.tilt_align); // otherwise the filter is "too rigid" to follow a position drift if (continuing_conditions_passing) { Vector3f vel_obs{0, 0, 0}; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 5d3f282d64..4b27a5bf2c 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -312,6 +312,13 @@ bool EKF2::multi_init(int imu, int mag) #endif // CONFIG_EKF2_RANGE_FINDER + + // mag advertise + if (_param_ekf2_mag_type.get() != MagFuseType::NONE) { + _estimator_aid_src_mag_heading_pub.advertise(); + _estimator_aid_src_mag_pub.advertise(); + } + _attitude_pub.advertise(); _local_position_pub.advertise(); _global_position_pub.advertise(); @@ -910,6 +917,24 @@ void EKF2::VerifyParams() } #endif // CONFIG_EKF2_OPTICAL_FLOW + + + // EKF2_MAG_TYPE obsolete options + if ((_param_ekf2_mag_type.get() != MagFuseType::AUTO) + && (_param_ekf2_mag_type.get() != MagFuseType::HEADING) + && (_param_ekf2_mag_type.get() != MagFuseType::NONE) + ) { + + mavlink_log_critical(&_mavlink_log_pub, "EKF2_MAG_TYPE invalid, resetting to default"); + /* EVENT + * @description EKF2_AID_MASK is set to {1:.0}. + */ + events::send(events::ID("ekf2_mag_type_invalid"), events::Log::Warning, + "EKF2_MAG_TYPE invalid, resetting to default", _param_ekf2_mag_type.get()); + + _param_ekf2_mag_type.set(0); + _param_ekf2_mag_type.commit(); + } } void EKF2::PublishAidSourceStatus(const hrt_abstime ×tamp) @@ -1570,31 +1595,37 @@ void EKF2::PublishSensorBias(const hrt_abstime ×tamp) // take device ids from sensor_selection_s if not using specific vehicle_imu_s if ((_device_id_gyro != 0) && (_param_ekf2_imu_ctrl.get() & static_cast(ImuCtrl::GyroBias))) { + const Vector3f bias_var{_ekf.getGyroBiasVariance()}; + bias.gyro_device_id = _device_id_gyro; gyro_bias.copyTo(bias.gyro_bias); bias.gyro_bias_limit = _ekf.getGyroBiasLimit(); - _ekf.getGyroBiasVariance().copyTo(bias.gyro_bias_variance); - bias.gyro_bias_valid = true; // TODO + bias_var.copyTo(bias.gyro_bias_variance); + bias.gyro_bias_valid = bias_var.longerThan(0.f) && !bias_var.longerThan(0.1f); bias.gyro_bias_stable = _gyro_cal.cal_available; _last_gyro_bias_published = gyro_bias; } if ((_device_id_accel != 0) && (_param_ekf2_imu_ctrl.get() & static_cast(ImuCtrl::AccelBias))) { + const Vector3f bias_var{_ekf.getAccelBiasVariance()}; + bias.accel_device_id = _device_id_accel; accel_bias.copyTo(bias.accel_bias); bias.accel_bias_limit = _ekf.getAccelBiasLimit(); - _ekf.getAccelBiasVariance().copyTo(bias.accel_bias_variance); - bias.accel_bias_valid = true; // TODO + bias_var.copyTo(bias.accel_bias_variance); + bias.accel_bias_valid = bias_var.longerThan(0.f) && !bias_var.longerThan(0.1f); bias.accel_bias_stable = _accel_cal.cal_available; _last_accel_bias_published = accel_bias; } if (_device_id_mag != 0) { + const Vector3f bias_var{_ekf.getMagBiasVariance()}; + bias.mag_device_id = _device_id_mag; mag_bias.copyTo(bias.mag_bias); bias.mag_bias_limit = _ekf.getMagBiasLimit(); - _ekf.getMagBiasVariance().copyTo(bias.mag_bias_variance); - bias.mag_bias_valid = true; // TODO + bias_var.copyTo(bias.mag_bias_variance); + bias.mag_bias_valid = bias_var.longerThan(0.f) && !bias_var.longerThan(0.1f); bias.mag_bias_stable = _mag_cal.cal_available; _last_mag_bias_published = mag_bias; } @@ -1738,6 +1769,8 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_fake_pos = _ekf.control_status_flags().fake_pos; status_flags.cs_fake_hgt = _ekf.control_status_flags().fake_hgt; status_flags.cs_gravity_vector = _ekf.control_status_flags().gravity_vector; + status_flags.cs_mag = _ekf.control_status_flags().mag; + status_flags.cs_ev_yaw_fault = _ekf.control_status_flags().ev_yaw_fault; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; @@ -2523,14 +2556,16 @@ void EKF2::UpdateGyroCalibration(const hrt_abstime ×tamp) void EKF2::UpdateMagCalibration(const hrt_abstime ×tamp) { - const bool bias_valid = (_ekf.control_status_flags().mag_hdg || _ekf.control_status_flags().mag_3D) - && !_ekf.control_status_flags().mag_fault - && !_ekf.control_status_flags().mag_field_disturbed; + const Vector3f mag_bias = _ekf.getMagBias(); + const Vector3f mag_bias_var = _ekf.getMagBiasVariance(); - const bool learning_valid = bias_valid && _ekf.control_status_flags().mag_3D; + const bool bias_valid = (_ekf.fault_status().value == 0) + && _ekf.control_status_flags().yaw_align + && mag_bias_var.longerThan(0.f) && !mag_bias_var.longerThan(0.02f); - UpdateCalibration(timestamp, _mag_cal, _ekf.getMagBias(), _ekf.getMagBiasVariance(), _ekf.getMagBiasLimit(), - bias_valid, learning_valid); + const bool learning_valid = bias_valid && _ekf.control_status_flags().mag; + + UpdateCalibration(timestamp, _mag_cal, mag_bias, mag_bias_var, _ekf.getMagBiasLimit(), bias_valid, learning_valid); // update stored declination value if (!_mag_decl_saved) { diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index 509ec723d9..76fd6192a9 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -493,16 +493,10 @@ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7); * The fusion of magnetometer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field. * If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable. * If set to 'Magnetic heading' magnetic heading fusion is used at all times. - * If set to '3-axis' 3-axis field fusion is used at all times. - * If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. - * If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. * If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). * @group EKF2 * @value 0 Automatic * @value 1 Magnetic heading - * @value 2 3-axis - * @value 3 VTOL custom - * @value 4 MC custom * @value 5 None * @reboot_required true */ 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 01ec200577..2f2cce5acc 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -1,391 +1,391 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,4.9e-07,0.0025,0.0025,0.005,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -90000,1,-0.0096,-0.01,-0.02,-0.0004,0.0026,-0.026,-1.4e-05,0.00011,-0.0023,0,0,0,0,0,0,0.19,-9.3e-10,0.4,0,0,0,0,0,5.2e-07,0.0026,0.0026,0.0051,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -190000,1,-0.0096,-0.011,-0.02,0.0002,0.0039,-0.041,6e-06,0.00043,-0.0044,-3e-11,-2.3e-12,4.9e-13,0,0,-2e-09,0.19,-9.3e-10,0.4,0,0,0,0,0,5.8e-07,0.0027,0.0027,0.0052,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -290000,1,-0.0097,-0.011,-0.02,0.0012,0.0063,-0.053,5e-05,0.00036,-0.007,9.1e-10,9.1e-11,-2.1e-11,0,0,-4.8e-07,0.19,-9.3e-10,0.4,0,0,0,0,0,6.8e-07,0.0029,0.0029,0.0054,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -390000,1,-0.0089,-0.012,0.046,0.0026,0.0083,-0.059,0.00024,0.0011,-0.0094,-1.1e-08,2.8e-09,2.7e-10,0,0,-4.5e-06,0.17,0.0017,0.41,0,0,0,0,0,7e-07,0.0031,0.0031,0.0056,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -490000,0.87,-0.0023,-0.015,0.5,0.0023,0.0057,-0.06,0.0002,0.00051,-0.011,1.6e-06,-3.8e-07,-4.1e-08,0,0,-1.6e-05,0.14,0.0014,0.42,0,0,0,0,0,2.9e-06,0.0033,0.0033,0.0058,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -590000,0.76,0.00067,-0.015,0.65,0.00071,0.0084,-0.059,0.00037,0.0012,-0.012,1.6e-06,-3.5e-07,-3.8e-08,0,0,-3.4e-05,0.18,0.0018,0.43,0,0,0,0,0,1.9e-05,0.0036,0.0036,0.0061,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -690000,0.72,0.0016,-0.016,0.69,-0.00082,0.0075,-0.06,7.2e-05,0.00069,-0.013,5.4e-06,-2.4e-06,-1.7e-07,0,0,-6.3e-05,0.2,0.002,0.43,0,0,0,0,0,5.9e-05,0.0039,0.0039,0.0064,2.6,2.6,2.8,0.26,0.26,0.29,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -790000,0.71,0.002,-0.016,0.7,-0.0028,0.0098,-0.063,-9.3e-05,0.0015,-0.014,5.3e-06,-2.3e-06,-1.6e-07,0,0,-9.5e-05,0.2,0.002,0.43,0,0,0,0,0,0.00012,0.0042,0.0042,0.0066,2.7,2.7,2,0.42,0.42,0.28,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -890000,0.71,0.0021,-0.016,0.7,-0.0034,0.011,-0.077,-0.00019,0.0011,-0.021,1.7e-05,-9e-06,-6.6e-07,0,0,-9.5e-05,0.2,0.002,0.43,0,0,0,0,0,0.00021,0.0046,0.0046,0.0069,1.3,1.3,2,0.2,0.2,0.43,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -990000,0.7,0.0025,-0.016,0.71,-0.0038,0.015,-0.092,-0.00057,0.0024,-0.029,1.7e-05,-9e-06,-6.6e-07,0,0,-9.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00033,0.005,0.005,0.0073,1.4,1.4,2,0.3,0.3,0.61,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1090000,0.7,0.0025,-0.017,0.71,-0.0034,0.016,-0.11,-0.00043,0.0019,-0.039,5.5e-05,-3.7e-05,-2.5e-06,0,0,-9.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00047,0.0053,0.0053,0.0076,0.89,0.89,2,0.17,0.17,0.84,0.0099,0.0099,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1190000,0.7,0.0027,-0.017,0.71,-0.0037,0.02,-0.12,-0.00079,0.0037,-0.051,5.5e-05,-3.7e-05,-2.5e-06,0,0,-9.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00064,0.0058,0.0058,0.008,1.1,1.1,2,0.24,0.24,1.1,0.0099,0.0099,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1290000,0.7,0.0028,-0.017,0.71,-0.0034,0.02,-0.14,-0.00055,0.0028,-0.064,0.00014,-0.00013,-7.3e-06,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.00083,0.006,0.006,0.0084,0.84,0.84,2,0.15,0.15,1.4,0.0096,0.0096,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1390000,0.7,0.0029,-0.017,0.71,-0.0032,0.026,-0.15,-0.0009,0.0052,-0.078,0.00014,-0.00013,-7.3e-06,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.001,0.0066,0.0066,0.0088,1.1,1.1,2,0.21,0.21,1.7,0.0096,0.0096,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1490000,0.7,0.0027,-0.017,0.71,-0.0024,0.025,-0.16,-0.0006,0.0039,-0.093,0.00029,-0.00034,-1.7e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.0013,0.0063,0.0063,0.0093,0.9,0.9,2,0.14,0.14,2.1,0.009,0.009,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1590000,0.7,0.0029,-0.018,0.71,-0.0029,0.031,-0.18,-0.00087,0.0066,-0.11,0.00029,-0.00034,-1.7e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.0016,0.0069,0.0069,0.0097,1.2,1.2,2,0.2,0.2,2.6,0.009,0.009,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1690000,0.7,0.0025,-0.018,0.71,0.00055,0.028,-0.19,-0.00048,0.0047,-0.13,0.0005,-0.0007,-3.1e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.0018,0.0061,0.006,0.01,0.97,0.97,2,0.13,0.13,3,0.0081,0.0081,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1790000,0.7,0.0027,-0.018,0.71,0.0025,0.036,-0.2,-0.00035,0.0078,-0.15,0.0005,-0.0007,-3.1e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.0022,0.0066,0.0066,0.011,1.3,1.3,2,0.2,0.2,3.5,0.0081,0.0081,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1890000,0.7,0.003,-0.018,0.72,0.0038,0.044,-0.22,-2.9e-05,0.012,-0.17,0.0005,-0.0007,-3.1e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.0025,0.0073,0.0073,0.011,1.6,1.6,2,0.3,0.3,4.1,0.0081,0.0081,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1990000,0.7,0.0025,-0.018,0.72,0.0056,0.037,-0.23,0.00047,0.0085,-0.19,0.00068,-0.0012,-4.8e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0029,0.0059,0.0059,0.012,1.3,1.3,2,0.2,0.2,4.7,0.007,0.007,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2090000,0.7,0.0026,-0.018,0.72,0.0083,0.043,-0.24,0.0012,0.012,-0.22,0.00068,-0.0012,-4.8e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0033,0.0064,0.0064,0.012,1.6,1.6,2.1,0.3,0.3,5.3,0.007,0.007,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2190000,0.7,0.0021,-0.018,0.72,0.0084,0.034,-0.26,0.0012,0.0083,-0.24,0.0008,-0.0018,-6.3e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0037,0.0049,0.0049,0.013,1.2,1.2,2.1,0.19,0.19,6,0.0058,0.0058,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2290000,0.7,0.0021,-0.018,0.72,0.011,0.041,-0.27,0.0022,0.012,-0.27,0.0008,-0.0018,-6.3e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0041,0.0054,0.0054,0.014,1.5,1.5,2.1,0.29,0.29,6.7,0.0058,0.0058,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2390000,0.7,0.0016,-0.017,0.72,0.011,0.031,-0.29,0.0019,0.0078,-0.3,0.00083,-0.0024,-7.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0046,0.004,0.004,0.014,1,1,2.1,0.19,0.19,7.4,0.0049,0.0049,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2490000,0.7,0.0017,-0.018,0.72,0.014,0.036,-0.3,0.0031,0.011,-0.32,0.00083,-0.0024,-7.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0051,0.0044,0.0044,0.015,1.3,1.3,2.1,0.27,0.27,8.2,0.0049,0.0049,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2590000,0.7,0.0014,-0.017,0.72,0.012,0.027,-0.31,0.0023,0.0071,-0.36,0.0008,-0.0028,-8.4e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0056,0.0033,0.0033,0.016,0.89,0.89,2.1,0.18,0.18,9.1,0.0041,0.0041,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2690000,0.7,0.0014,-0.017,0.72,0.015,0.031,-0.33,0.0037,0.01,-0.39,0.0008,-0.0028,-8.4e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0062,0.0036,0.0036,0.016,1.1,1.1,2.2,0.25,0.25,10,0.0041,0.0041,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2790000,0.7,0.0012,-0.017,0.72,0.014,0.024,-0.34,0.0027,0.0064,-0.42,0.00071,-0.0033,-9e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0068,0.0028,0.0028,0.017,0.77,0.77,2.2,0.16,0.16,11,0.0034,0.0034,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2890000,0.7,0.0012,-0.017,0.72,0.016,0.027,-0.35,0.0041,0.0089,-0.46,0.00071,-0.0033,-9e-05,0,0,-0.00012,0.21,0.0021,0.43,0,0,0,0,0,0.0074,0.0031,0.003,0.018,0.96,0.96,2.2,0.23,0.23,12,0.0034,0.0034,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -2990000,0.7,0.0011,-0.017,0.72,0.014,0.022,-0.36,0.003,0.0058,-0.49,0.0006,-0.0036,-9.4e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.008,0.0024,0.0024,0.019,0.68,0.68,2.2,0.15,0.15,13,0.0029,0.0029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3090000,0.7,0.0011,-0.017,0.72,0.017,0.024,-0.38,0.0045,0.0081,-0.53,0.0006,-0.0036,-9.4e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0087,0.0026,0.0026,0.02,0.84,0.84,2.2,0.22,0.22,14,0.0029,0.0029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3190000,0.7,0.0009,-0.017,0.72,0.014,0.019,-0.39,0.0032,0.0053,-0.57,0.00046,-0.0039,-9.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.0093,0.0021,0.0021,0.021,0.6,0.6,2.3,0.14,0.14,15,0.0025,0.0025,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3290000,0.7,0.00089,-0.017,0.72,0.017,0.023,-0.4,0.0047,0.0074,-0.61,0.00046,-0.0039,-9.6e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.01,0.0023,0.0023,0.021,0.74,0.74,2.3,0.2,0.2,16,0.0025,0.0025,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3390000,0.7,0.00085,-0.017,0.72,0.015,0.018,-0.42,0.0033,0.0049,-0.65,0.00031,-0.0042,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.011,0.0018,0.0018,0.022,0.54,0.54,2.3,0.14,0.14,17,0.0021,0.0021,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3490000,0.7,0.00086,-0.017,0.72,0.019,0.021,-0.43,0.005,0.0068,-0.69,0.00031,-0.0042,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.012,0.002,0.002,0.023,0.67,0.67,2.3,0.19,0.19,19,0.0021,0.0021,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3590000,0.7,0.00079,-0.017,0.72,0.017,0.016,-0.44,0.0036,0.0045,-0.73,0.00015,-0.0044,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.012,0.0016,0.0016,0.024,0.5,0.5,2.4,0.13,0.13,20,0.0018,0.0018,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3690000,0.7,0.00079,-0.017,0.72,0.021,0.018,-0.46,0.0055,0.0063,-0.78,0.00015,-0.0044,-9.7e-05,0,0,-0.00011,0.21,0.0021,0.43,0,0,0,0,0,0.013,0.0018,0.0018,0.025,0.61,0.61,2.4,0.18,0.18,21,0.0018,0.0018,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3790000,0.7,0.00073,-0.017,0.72,0.02,0.014,-0.47,0.004,0.0042,-0.83,-3.1e-05,-0.0046,-9.5e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.014,0.0015,0.0014,0.026,0.46,0.46,2.4,0.12,0.12,23,0.0015,0.0015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3890000,0.7,0.00077,-0.017,0.72,0.022,0.016,-0.48,0.0061,0.0057,-0.87,-3.1e-05,-0.0046,-9.5e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.015,0.0016,0.0016,0.027,0.56,0.56,2.4,0.17,0.17,24,0.0015,0.0015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -3990000,0.7,0.00081,-0.017,0.72,0.025,0.019,-0.5,0.0084,0.0074,-0.92,-3.1e-05,-0.0046,-9.5e-05,0,0,-0.0001,0.21,0.0021,0.43,0,0,0,0,0,0.016,0.0018,0.0017,0.028,0.68,0.68,2.5,0.23,0.23,26,0.0015,0.0015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4090000,0.7,0.00079,-0.016,0.72,0.021,0.016,-0.51,0.0062,0.0053,-0.97,-0.00022,-0.0048,-9.3e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.017,0.0014,0.0014,0.029,0.52,0.52,2.5,0.16,0.16,27,0.0012,0.0012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4190000,0.7,0.00077,-0.016,0.72,0.025,0.018,-0.53,0.0086,0.007,-1,-0.00022,-0.0048,-9.3e-05,0,0,-9.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.018,0.0016,0.0015,0.03,0.63,0.63,2.5,0.22,0.22,29,0.0012,0.0012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4290000,0.7,0.0008,-0.016,0.72,0.019,0.015,-0.54,0.0063,0.005,-1.1,-0.00041,-0.005,-9e-05,0,0,-9.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.018,0.0013,0.0012,0.032,0.48,0.48,2.6,0.15,0.15,31,0.001,0.001,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4390000,0.7,0.00068,-0.016,0.71,0.021,0.016,-0.55,0.0083,0.0066,-1.1,-0.00041,-0.005,-9e-05,0,0,-9.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.019,0.0014,0.0014,0.033,0.58,0.58,2.6,0.2,0.2,33,0.001,0.001,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4490000,0.7,0.00073,-0.016,0.71,0.017,0.013,-0.57,0.0058,0.0046,-1.2,-0.00059,-0.0051,-8.8e-05,0,0,-8.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.02,0.0011,0.0011,0.034,0.44,0.44,2.6,0.14,0.14,34,0.00083,0.00083,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4590000,0.7,0.00069,-0.016,0.71,0.019,0.015,-0.58,0.0076,0.006,-1.2,-0.00059,-0.0051,-8.8e-05,0,0,-8.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.022,0.0012,0.0012,0.035,0.53,0.53,2.7,0.19,0.19,36,0.00083,0.00083,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4690000,0.7,0.0007,-0.016,0.71,0.016,0.012,-0.6,0.0054,0.0043,-1.3,-0.00074,-0.0052,-8.6e-05,0,0,-8.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.023,0.00097,0.00095,0.036,0.41,0.41,2.7,0.14,0.14,38,0.00068,0.00068,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4790000,0.7,0.00063,-0.016,0.71,0.018,0.014,-0.61,0.0071,0.0056,-1.4,-0.00074,-0.0052,-8.6e-05,0,0,-8.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.024,0.0011,0.001,0.038,0.49,0.49,2.7,0.18,0.18,40,0.00068,0.00068,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4890000,0.7,0.00065,-0.016,0.71,0.016,0.011,-0.63,0.0051,0.0039,-1.4,-0.00088,-0.0053,-8.4e-05,0,0,-7.9e-05,0.21,0.0021,0.43,0,0,0,0,0,0.025,0.00085,0.00083,0.039,0.37,0.37,2.8,0.13,0.13,42,0.00055,0.00055,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -4990000,0.7,0.00068,-0.016,0.71,0.017,0.013,-0.64,0.0068,0.0051,-1.5,-0.00088,-0.0053,-8.4e-05,0,0,-7.9e-05,0.21,0.0021,0.43,0,0,0,0,0,0.026,0.00092,0.00089,0.04,0.44,0.44,2.8,0.17,0.17,44,0.00055,0.00055,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5090000,0.7,0.00069,-0.015,0.71,0.014,0.01,-0.66,0.0049,0.0036,-1.6,-0.001,-0.0054,-8.3e-05,0,0,-7.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.027,0.00074,0.00071,0.042,0.34,0.34,2.8,0.13,0.13,46,0.00044,0.00044,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5190000,0.7,0.00068,-0.015,0.71,0.016,0.011,-0.67,0.0064,0.0047,-1.6,-0.001,-0.0054,-8.3e-05,0,0,-7.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.028,0.00079,0.00077,0.043,0.4,0.4,2.9,0.16,0.16,49,0.00044,0.00044,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5290000,0.7,0.00075,-0.015,0.71,0.012,0.0072,-0.68,0.0046,0.0033,-1.7,-0.0011,-0.0055,-8.2e-05,0,0,-7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.029,0.00064,0.00062,0.044,0.31,0.31,2.9,0.12,0.12,51,0.00036,0.00036,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5390000,0.7,0.00084,-0.015,0.71,0.014,0.0066,-0.7,0.0058,0.0039,-1.8,-0.0011,-0.0055,-8.2e-05,0,0,-7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.031,0.00068,0.00066,0.046,0.37,0.37,2.9,0.16,0.16,53,0.00036,0.00036,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5490000,0.7,0.00091,-0.015,0.71,0.011,0.0042,-0.71,0.0042,0.0026,-1.8,-0.0012,-0.0055,-8.1e-05,0,0,-6.7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.032,0.00055,0.00053,0.047,0.28,0.28,3,0.11,0.11,56,0.00029,0.00029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5590000,0.7,0.00092,-0.015,0.71,0.012,0.0047,-0.73,0.0053,0.003,-1.9,-0.0012,-0.0055,-8.1e-05,0,0,-6.7e-05,0.21,0.0021,0.43,0,0,0,0,0,0.033,0.00059,0.00057,0.049,0.33,0.33,3,0.15,0.15,58,0.00029,0.00029,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5690000,0.7,0.001,-0.015,0.71,0.0081,0.003,-0.74,0.0037,0.002,-2,-0.0013,-0.0056,-8e-05,0,0,-6.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.035,0.00048,0.00046,0.05,0.26,0.26,3.1,0.11,0.11,61,0.00023,0.00023,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5790000,0.7,0.0011,-0.015,0.71,0.0074,0.0032,-0.75,0.0045,0.0023,-2.1,-0.0013,-0.0056,-8e-05,0,0,-6.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.036,0.00051,0.00049,0.052,0.3,0.3,3.1,0.14,0.14,64,0.00023,0.00023,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5890000,0.7,0.0011,-0.015,0.71,0.0048,0.0028,0.0028,0.003,0.0016,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-6.4e-05,0.21,0.0021,0.43,0,0,0,0,0,0.037,0.00042,0.00039,0.053,0.23,0.23,9.8,0.11,0.11,0.52,0.00019,0.00019,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -5990000,0.7,0.0011,-0.015,0.71,0.0037,0.0029,0.015,0.0034,0.0018,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-7.3e-05,0.21,0.0021,0.43,0,0,0,0,0,0.039,0.00044,0.00042,0.055,0.27,0.27,8.8,0.13,0.13,0.33,0.00019,0.00019,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6090000,0.7,0.0011,-0.015,0.71,0.0029,0.0038,-0.011,0.0037,0.0022,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-6.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.04,0.00047,0.00045,0.056,0.32,0.32,7,0.17,0.17,0.33,0.00019,0.00019,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6190000,0.7,0.0011,-0.015,0.71,-0.00035,0.0027,-0.005,0.0022,0.0015,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-8.8e-05,0.21,0.0021,0.43,0,0,0,0,0,0.041,0.00039,0.00036,0.058,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6290000,0.7,0.0011,-0.015,0.71,-6.8e-05,0.0039,-0.012,0.0022,0.0019,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0,0,-9.6e-05,0.21,0.0021,0.43,0,0,0,0,0,0.043,0.00041,0.00038,0.059,0.29,0.29,3.2,0.16,0.16,0.3,0.00015,0.00015,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6390000,0.7,0.0012,-0.014,0.71,-0.0018,0.0033,-0.05,0.0012,0.0014,-3.7e+02,-0.0014,-0.0056,-8e-05,0,0,-3.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.044,0.00034,0.00031,0.061,0.23,0.23,2.3,0.12,0.12,0.29,0.00013,0.00012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6490000,0.7,0.0012,-0.015,0.71,-0.0017,0.0039,-0.052,0.001,0.0018,-3.7e+02,-0.0014,-0.0056,-8e-05,0,0,-8.5e-05,0.21,0.0021,0.43,0,0,0,0,0,0.046,0.00036,0.00033,0.063,0.26,0.26,1.5,0.15,0.15,0.26,0.00013,0.00012,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6590000,0.71,0.0012,-0.015,0.71,-0.0024,0.0029,-0.099,0.00044,0.0014,-3.7e+02,-0.0014,-0.0057,4e-05,0,0,9.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0049,0.00026,0.00026,0.0018,0.19,0.19,1.1,0.12,0.12,0.23,0.0001,0.0001,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6690000,0.7,0.0012,-0.015,0.71,-0.0016,0.0037,-0.076,0.00024,0.0017,-3.7e+02,-0.0014,-0.0056,-0.00051,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0042,0.00026,0.00026,0.0008,0.19,0.19,0.78,0.14,0.14,0.21,0.0001,0.0001,0.0099,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6790000,0.71,0.0012,-0.014,0.71,-0.0026,0.0034,-0.11,3.7e-05,0.0021,-3.7e+02,-0.0014,-0.0057,-0.00012,0,0,1e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0041,0.00026,0.00026,0.00055,0.2,0.2,0.6,0.17,0.17,0.2,0.0001,0.0001,0.0098,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6890000,0.71,0.0012,-0.014,0.71,-0.0042,0.0037,-0.12,-0.00032,0.0025,-3.7e+02,-0.0014,-0.0057,0.00023,0,0,-4.1e-05,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00026,0.00026,0.00042,0.21,0.21,0.46,0.21,0.21,0.18,0.0001,0.0001,0.0096,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6990000,0.7,0.0013,-0.014,0.71,-0.0039,0.0042,-0.12,-0.00073,0.0028,-3.7e+02,-0.0014,-0.0056,-0.0017,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00026,0.00026,0.00036,0.22,0.22,0.36,0.25,0.25,0.16,0.0001,0.0001,0.0093,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7090000,0.7,0.0013,-0.014,0.71,-0.004,0.0034,-0.13,-0.0011,0.003,-3.7e+02,-0.0015,-0.0056,-0.0039,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00034,0.23,0.23,0.29,0.29,0.29,0.16,0.0001,0.0001,0.0088,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7190000,0.7,0.0013,-0.014,0.71,-0.0053,0.0033,-0.15,-0.0016,0.0033,-3.7e+02,-0.0015,-0.0056,-0.0043,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00033,0.25,0.25,0.24,0.34,0.34,0.15,0.0001,0.0001,0.0082,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7290000,0.7,0.0013,-0.014,0.71,-0.0064,0.0034,-0.15,-0.0022,0.0037,-3.7e+02,-0.0014,-0.0056,-0.0035,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00027,0.00027,0.00032,0.27,0.27,0.2,0.4,0.4,0.14,0.0001,0.0001,0.0075,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7390000,0.7,0.0013,-0.014,0.71,-0.006,0.0047,-0.16,-0.0028,0.0042,-3.7e+02,-0.0014,-0.0056,-0.0027,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00028,0.00028,0.00033,0.29,0.29,0.18,0.46,0.46,0.13,0.0001,0.0001,0.0068,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7490000,0.7,0.0014,-0.014,0.71,-0.0072,0.0049,-0.16,-0.0035,0.0047,-3.7e+02,-0.0014,-0.0056,-0.0022,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00028,0.00028,0.00032,0.32,0.32,0.15,0.53,0.53,0.12,0.0001,9.9e-05,0.006,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7590000,0.7,0.0014,-0.014,0.71,-0.0086,0.0061,-0.17,-0.0042,0.0054,-3.7e+02,-0.0014,-0.0057,-0.00052,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00029,0.00028,0.00032,0.35,0.35,0.14,0.6,0.6,0.12,0.0001,9.9e-05,0.0053,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7690000,0.7,0.0014,-0.014,0.71,-0.0099,0.0067,-0.16,-0.0051,0.006,-3.7e+02,-0.0014,-0.0057,-0.0005,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00029,0.00029,0.00032,0.38,0.38,0.13,0.69,0.69,0.11,9.9e-05,9.9e-05,0.0047,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7790000,0.7,0.0015,-0.014,0.71,-0.011,0.0072,-0.16,-0.0061,0.0064,-3.7e+02,-0.0014,-0.0056,-0.0025,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.0003,0.0003,0.00031,0.41,0.41,0.12,0.78,0.78,0.11,9.8e-05,9.8e-05,0.004,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7890000,0.7,0.0015,-0.014,0.71,-0.013,0.0089,-0.16,-0.0073,0.0073,-3.7e+02,-0.0014,-0.0056,-0.0013,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.0003,0.0003,0.00031,0.45,0.45,0.11,0.89,0.89,0.1,9.8e-05,9.8e-05,0.0035,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -7990000,0.7,0.0015,-0.014,0.71,-0.014,0.0099,-0.16,-0.0086,0.0083,-3.7e+02,-0.0014,-0.0057,-0.00039,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00031,0.00031,0.0003,0.49,0.49,0.1,1,1,0.099,9.7e-05,9.7e-05,0.003,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -8090000,0.7,0.0015,-0.014,0.71,-0.016,0.011,-0.17,-0.01,0.0095,-3.7e+02,-0.0014,-0.0057,0.00082,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00032,0.00031,0.00029,0.53,0.53,0.1,1.1,1.1,0.097,9.7e-05,9.7e-05,0.0026,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8190000,0.7,0.0015,-0.014,0.71,-0.018,0.012,-0.18,-0.012,0.01,-3.7e+02,-0.0014,-0.0057,-0.00029,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00032,0.00032,0.00028,0.58,0.58,0.099,1.3,1.3,0.094,9.7e-05,9.7e-05,0.0023,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8290000,0.7,0.0015,-0.014,0.71,-0.019,0.013,-0.17,-0.014,0.011,-3.7e+02,-0.0014,-0.0056,-0.00084,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00033,0.00033,0.00027,0.63,0.63,0.097,1.4,1.4,0.091,9.6e-05,9.6e-05,0.002,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -8390000,0.7,0.0016,-0.014,0.71,-0.02,0.014,-0.17,-0.016,0.013,-3.7e+02,-0.0014,-0.0057,0.00015,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00034,0.00034,0.00027,0.68,0.68,0.097,1.6,1.6,0.091,9.6e-05,9.6e-05,0.0018,0.04,0.04,0.035,0,0,0,0,0,0,0,0 -8490000,0.7,0.0015,-0.014,0.71,-0.021,0.015,-0.17,-0.017,0.014,-3.7e+02,-0.0014,-0.0057,-0.00022,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00034,0.00034,0.00026,0.73,0.73,0.096,1.8,1.8,0.089,9.5e-05,9.5e-05,0.0015,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8590000,0.7,0.0016,-0.014,0.71,-0.023,0.017,-0.17,-0.02,0.015,-3.7e+02,-0.0014,-0.0056,-0.00092,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00035,0.00035,0.00025,0.79,0.79,0.095,2,2,0.088,9.5e-05,9.5e-05,0.0013,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8690000,0.7,0.0016,-0.014,0.71,-0.026,0.018,-0.16,-0.022,0.017,-3.7e+02,-0.0014,-0.0057,9e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00036,0.00036,0.00024,0.84,0.84,0.096,2.2,2.2,0.088,9.4e-05,9.4e-05,0.0012,0.04,0.04,0.033,0,0,0,0,0,0,0,0 -8790000,0.7,0.0016,-0.014,0.71,-0.027,0.019,-0.15,-0.025,0.018,-3.7e+02,-0.0014,-0.0057,-0.00031,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00037,0.00037,0.00023,0.91,0.91,0.095,2.5,2.5,0.087,9.4e-05,9.4e-05,0.0011,0.04,0.04,0.032,0,0,0,0,0,0,0,0 -8890000,0.7,0.0016,-0.014,0.71,-0.029,0.02,-0.15,-0.027,0.02,-3.7e+02,-0.0014,-0.0057,-0.00051,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.004,0.00037,0.00037,0.00022,0.96,0.96,0.095,2.7,2.7,0.086,9.2e-05,9.2e-05,0.00094,0.04,0.04,0.03,0,0,0,0,0,0,0,0 -8990000,0.7,0.0016,-0.014,0.71,-0.03,0.02,-0.14,-0.03,0.021,-3.7e+02,-0.0014,-0.0056,-0.001,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00038,0.00038,0.00022,1,1,0.096,3,3,0.087,9.2e-05,9.2e-05,0.00085,0.04,0.04,0.029,0,0,0,0,0,0,0,0 -9090000,0.7,0.0017,-0.014,0.71,-0.032,0.02,-0.14,-0.033,0.022,-3.7e+02,-0.0014,-0.0056,-0.0012,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00038,0.00038,0.00021,1.1,1.1,0.095,3.3,3.3,0.086,9.1e-05,9.1e-05,0.00076,0.04,0.04,0.028,0,0,0,0,0,0,0,0 -9190000,0.7,0.0017,-0.014,0.71,-0.033,0.021,-0.14,-0.036,0.025,-3.7e+02,-0.0014,-0.0057,-9.6e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00039,0.00039,0.0002,1.2,1.2,0.094,3.6,3.6,0.085,9.1e-05,9.1e-05,0.00068,0.04,0.04,0.027,0,0,0,0,0,0,0,0 -9290000,0.7,0.0016,-0.014,0.71,-0.033,0.022,-0.14,-0.038,0.026,-3.7e+02,-0.0014,-0.0057,1.3e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00039,0.00039,0.0002,1.2,1.2,0.093,3.9,3.9,0.085,8.9e-05,8.9e-05,0.00061,0.04,0.04,0.025,0,0,0,0,0,0,0,0 -9390000,0.7,0.0016,-0.014,0.71,-0.034,0.024,-0.14,-0.042,0.028,-3.7e+02,-0.0014,-0.0057,2.6e-07,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.0004,0.00019,1.3,1.3,0.093,4.3,4.3,0.086,8.9e-05,8.9e-05,0.00056,0.04,0.04,0.024,0,0,0,0,0,0,0,0 -9490000,0.7,0.0016,-0.014,0.71,-0.034,0.023,-0.13,-0.044,0.029,-3.7e+02,-0.0013,-0.0057,0.00059,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.0004,0.0004,0.00019,1.3,1.3,0.091,4.6,4.6,0.085,8.7e-05,8.7e-05,0.0005,0.04,0.04,0.023,0,0,0,0,0,0,0,0 -9590000,0.7,0.0016,-0.014,0.71,-0.036,0.024,-0.13,-0.047,0.031,-3.7e+02,-0.0013,-0.0057,0.00069,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00018,1.4,1.4,0.09,5.1,5.1,0.085,8.7e-05,8.7e-05,0.00046,0.04,0.04,0.021,0,0,0,0,0,0,0,0 -9690000,0.7,0.0017,-0.014,0.71,-0.037,0.025,-0.12,-0.049,0.031,-3.7e+02,-0.0013,-0.0057,0.00013,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00018,1.4,1.4,0.089,5.3,5.3,0.086,8.5e-05,8.5e-05,0.00042,0.04,0.04,0.02,0,0,0,0,0,0,0,0 -9790000,0.7,0.0016,-0.014,0.71,-0.036,0.027,-0.11,-0.053,0.034,-3.7e+02,-0.0013,-0.0057,0.00044,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00017,1.5,1.5,0.087,5.9,5.9,0.085,8.5e-05,8.5e-05,0.00038,0.04,0.04,0.019,0,0,0,0,0,0,0,0 -9890000,0.7,0.0016,-0.014,0.71,-0.036,0.027,-0.11,-0.053,0.034,-3.7e+02,-0.0013,-0.0057,0.00037,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00017,1.5,1.5,0.084,6.1,6.1,0.085,8.2e-05,8.2e-05,0.00035,0.04,0.04,0.018,0,0,0,0,0,0,0,0 -9990000,0.7,0.0017,-0.014,0.71,-0.038,0.027,-0.1,-0.057,0.037,-3.7e+02,-0.0013,-0.0057,0.00015,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00016,1.6,1.6,0.083,6.7,6.7,0.086,8.2e-05,8.2e-05,0.00033,0.04,0.04,0.017,0,0,0,0,0,0,0,0 -10090000,0.7,0.0017,-0.014,0.71,-0.036,0.026,-0.096,-0.057,0.036,-3.7e+02,-0.0013,-0.0057,0.00023,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00041,0.00041,0.00016,1.6,1.6,0.08,6.9,6.9,0.085,8e-05,8e-05,0.0003,0.04,0.04,0.016,0,0,0,0,0,0,0,0 -10190000,0.7,0.0017,-0.014,0.71,-0.037,0.028,-0.096,-0.061,0.039,-3.7e+02,-0.0013,-0.0057,-0.00029,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00042,0.00042,0.00015,1.7,1.7,0.078,7.6,7.6,0.084,8e-05,8e-05,0.00027,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10290000,0.7,0.0017,-0.014,0.71,-0.038,0.028,-0.084,-0.065,0.041,-3.7e+02,-0.0013,-0.0057,-0.00057,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00043,0.00043,0.00015,1.8,1.8,0.076,8.3,8.3,0.085,8e-05,8e-05,0.00026,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10390000,0.7,0.0016,-0.014,0.71,0.01,-0.02,0.0096,0.0009,-0.0018,-3.7e+02,-0.0013,-0.0057,-0.00051,-6.4e-08,5.1e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00045,0.00045,0.00015,0.25,0.25,0.56,0.25,0.25,0.078,8e-05,8e-05,0.00024,0.04,0.04,0.013,0,0,0,0,0,0,0,0 -10490000,0.7,0.0017,-0.014,0.71,0.0097,-0.018,0.023,0.0019,-0.0036,-3.7e+02,-0.0013,-0.0057,-0.00073,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00046,0.00046,0.00014,0.26,0.26,0.55,0.26,0.26,0.08,8e-05,8e-05,0.00022,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10590000,0.7,0.0017,-0.014,0.71,0.0092,-0.0076,0.026,0.0018,-0.00084,-3.7e+02,-0.0013,-0.0057,-0.00066,-0.00028,7.5e-06,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0039,0.00047,0.00047,0.00014,0.13,0.13,0.27,0.13,0.13,0.073,7.9e-05,7.9e-05,0.0002,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10690000,0.7,0.0018,-0.014,0.71,0.0079,-0.0075,0.03,0.0027,-0.0016,-3.7e+02,-0.0013,-0.0057,-0.0007,-0.00028,8.7e-06,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00048,0.00014,0.14,0.14,0.26,0.14,0.14,0.078,7.9e-05,7.9e-05,0.00019,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10790000,0.7,0.0018,-0.014,0.71,0.0072,-0.0048,0.024,0.0028,-0.0008,-3.7e+02,-0.0013,-0.0056,-0.00062,-0.0005,7.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00047,0.00013,0.099,0.099,0.17,0.091,0.091,0.072,7.8e-05,7.8e-05,0.00018,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10890000,0.7,0.0017,-0.014,0.71,0.0067,-0.0041,0.02,0.0034,-0.0012,-3.7e+02,-0.0013,-0.0056,-0.00059,-0.0005,7e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00049,0.00049,0.00013,0.11,0.11,0.16,0.098,0.098,0.075,7.8e-05,7.8e-05,0.00016,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10990000,0.7,0.0017,-0.014,0.71,0.0086,0.00072,0.014,0.0048,-0.0024,-3.7e+02,-0.0013,-0.0056,-0.00034,-0.001,0.00061,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00047,0.00047,0.00013,0.09,0.09,0.12,0.073,0.073,0.071,7.5e-05,7.5e-05,0.00015,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11090000,0.7,0.0017,-0.014,0.71,0.0079,0.0025,0.019,0.0056,-0.0023,-3.7e+02,-0.0013,-0.0056,-0.00012,-0.001,0.00061,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00048,0.00048,0.00012,0.11,0.11,0.11,0.079,0.079,0.074,7.5e-05,7.5e-05,0.00014,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11190000,0.7,0.0017,-0.014,0.71,0.012,0.0053,0.0077,0.0067,-0.0031,-3.7e+02,-0.0012,-0.0056,-0.00025,-0.0013,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00044,0.00044,0.00012,0.088,0.088,0.084,0.063,0.063,0.069,7e-05,7e-05,0.00014,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11290000,0.7,0.0018,-0.014,0.71,0.012,0.0071,0.0074,0.0079,-0.0024,-3.7e+02,-0.0012,-0.0056,-0.00048,-0.0013,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00045,0.00045,0.00012,0.11,0.11,0.078,0.07,0.07,0.072,7e-05,7e-05,0.00013,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11390000,0.7,0.0019,-0.014,0.71,0.0072,0.0067,0.0017,0.0057,-0.0022,-3.7e+02,-0.0013,-0.0056,-0.00064,-0.00099,0.00053,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0004,0.0004,0.00012,0.089,0.089,0.063,0.057,0.057,0.068,6.5e-05,6.5e-05,0.00012,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11490000,0.7,0.0019,-0.014,0.71,0.0051,0.009,0.0025,0.0063,-0.0014,-3.7e+02,-0.0013,-0.0056,-0.00095,-0.00099,0.00053,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00041,0.00041,0.00011,0.11,0.11,0.058,0.065,0.065,0.069,6.5e-05,6.5e-05,0.00011,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11590000,0.7,0.0019,-0.014,0.71,0.00041,0.0084,-0.0034,0.0047,-0.0015,-3.7e+02,-0.0013,-0.0056,-0.00098,-0.00058,0.00027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00036,0.00036,0.00011,0.089,0.089,0.049,0.054,0.054,0.066,6e-05,6e-05,0.00011,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11690000,0.7,0.0018,-0.014,0.71,-0.0021,0.011,-0.0079,0.0046,-0.00059,-3.7e+02,-0.0013,-0.0056,-0.001,-0.00057,0.00026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00037,0.00037,0.00011,0.11,0.11,0.046,0.062,0.062,0.066,6e-05,6e-05,0.0001,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11790000,0.7,0.0019,-0.014,0.71,-0.0081,0.011,-0.0098,0.0021,0.00045,-3.7e+02,-0.0014,-0.0056,-0.001,-0.00051,-0.0001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00032,0.00032,0.00011,0.087,0.087,0.039,0.052,0.052,0.063,5.5e-05,5.6e-05,9.5e-05,0.036,0.036,0.01,0,0,0,0,0,0,0,0 -11890000,0.7,0.0019,-0.014,0.71,-0.0093,0.012,-0.011,0.0012,0.0016,-3.7e+02,-0.0014,-0.0056,-0.0011,-0.00052,-9.6e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00033,0.00033,0.00011,0.1,0.1,0.037,0.06,0.06,0.063,5.5e-05,5.6e-05,9e-05,0.036,0.036,0.01,0,0,0,0,0,0,0,0 -11990000,0.7,0.002,-0.014,0.71,-0.011,0.013,-0.016,-6.6e-05,0.0022,-3.7e+02,-0.0014,-0.0056,-0.0011,-0.00039,-0.00014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00029,0.00029,0.00011,0.083,0.083,0.033,0.051,0.051,0.061,5.1e-05,5.1e-05,8.5e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 -12090000,0.7,0.002,-0.014,0.71,-0.013,0.015,-0.022,-0.0013,0.0036,-3.7e+02,-0.0014,-0.0057,-0.0009,-0.00037,-0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00029,0.00029,0.0001,0.099,0.099,0.031,0.059,0.059,0.061,5.1e-05,5.1e-05,8.1e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 -12190000,0.7,0.0017,-0.014,0.71,-0.007,0.012,-0.017,0.0015,0.002,-3.7e+02,-0.0013,-0.0057,-0.00082,2.1e-05,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00026,0.00026,0.0001,0.079,0.079,0.028,0.05,0.05,0.059,4.8e-05,4.8e-05,7.6e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 -12290000,0.7,0.0017,-0.014,0.71,-0.0094,0.014,-0.016,0.00068,0.0033,-3.7e+02,-0.0013,-0.0057,-0.00077,-5.6e-06,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00027,0.00027,0.0001,0.093,0.093,0.028,0.058,0.058,0.059,4.8e-05,4.8e-05,7.3e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 -12390000,0.7,0.0014,-0.014,0.71,-0.0045,0.011,-0.015,0.0029,0.0018,-3.7e+02,-0.0012,-0.0057,-0.00083,0.00029,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00024,0.00024,9.8e-05,0.075,0.075,0.026,0.05,0.05,0.057,4.5e-05,4.5e-05,6.9e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 -12490000,0.7,0.0014,-0.014,0.71,-0.0056,0.013,-0.018,0.0024,0.003,-3.7e+02,-0.0012,-0.0057,-0.00092,0.00028,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00025,0.00025,9.6e-05,0.087,0.087,0.026,0.058,0.058,0.057,4.5e-05,4.5e-05,6.6e-05,0.035,0.035,0.01,0,0,0,0,0,0,0,0 -12590000,0.7,0.0015,-0.014,0.71,-0.013,0.011,-0.023,-0.0027,0.0016,-3.7e+02,-0.0013,-0.0058,-0.00089,0.00055,0.00061,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00022,0.00022,9.5e-05,0.07,0.07,0.025,0.049,0.049,0.055,4.3e-05,4.3e-05,6.3e-05,0.035,0.035,0.0099,0,0,0,0,0,0,0,0 -12690000,0.7,0.0015,-0.014,0.71,-0.013,0.012,-0.027,-0.0041,0.0028,-3.7e+02,-0.0013,-0.0058,-0.00094,0.00058,0.00059,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00023,0.00023,9.3e-05,0.081,0.081,0.025,0.058,0.058,0.055,4.3e-05,4.3e-05,6e-05,0.035,0.035,0.0098,0,0,0,0,0,0,0,0 -12790000,0.7,0.0015,-0.014,0.71,-0.019,0.0092,-0.03,-0.0075,0.0015,-3.7e+02,-0.0013,-0.0058,-0.00087,0.00074,0.00042,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00021,0.00021,9.2e-05,0.066,0.066,0.024,0.049,0.049,0.053,4e-05,4e-05,5.7e-05,0.035,0.035,0.0097,0,0,0,0,0,0,0,0 -12890000,0.7,0.0015,-0.014,0.71,-0.02,0.0092,-0.029,-0.0094,0.0024,-3.7e+02,-0.0013,-0.0058,-0.00082,0.00068,0.00047,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00022,0.00022,9.1e-05,0.076,0.076,0.025,0.057,0.057,0.054,4e-05,4e-05,5.4e-05,0.035,0.035,0.0096,0,0,0,0,0,0,0,0 -12990000,0.7,0.0012,-0.014,0.71,-0.0078,0.0067,-0.03,-0.0011,0.0013,-3.7e+02,-0.0012,-0.0058,-0.00068,0.00069,0.00098,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.9e-05,0.062,0.062,0.025,0.049,0.049,0.052,3.8e-05,3.9e-05,5.2e-05,0.035,0.035,0.0094,0,0,0,0,0,0,0,0 -13090000,0.7,0.0012,-0.014,0.71,-0.0084,0.0069,-0.03,-0.0019,0.002,-3.7e+02,-0.0012,-0.0058,-0.00078,0.00066,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00021,0.00021,8.8e-05,0.071,0.071,0.025,0.057,0.057,0.052,3.8e-05,3.9e-05,4.9e-05,0.035,0.035,0.0094,0,0,0,0,0,0,0,0 -13190000,0.7,0.00097,-0.014,0.71,0.00038,0.0064,-0.027,0.0043,0.0013,-3.7e+02,-0.0012,-0.0059,-0.00075,0.00053,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.6e-05,0.058,0.058,0.025,0.049,0.049,0.051,3.7e-05,3.7e-05,4.7e-05,0.035,0.035,0.0091,0,0,0,0,0,0,0,0 -13290000,0.7,0.00097,-0.014,0.71,0.0002,0.0073,-0.024,0.0043,0.002,-3.7e+02,-0.0012,-0.0059,-0.00063,0.0004,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.5e-05,0.067,0.067,0.027,0.057,0.057,0.051,3.7e-05,3.7e-05,4.5e-05,0.035,0.035,0.0091,0,0,0,0,0,0,0,0 -13390000,0.7,0.00082,-0.014,0.71,0.00098,0.0062,-0.02,0.0032,0.0012,-3.7e+02,-0.0011,-0.0059,-0.00053,0.00027,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,8.4e-05,0.055,0.055,0.026,0.048,0.048,0.05,3.5e-05,3.5e-05,4.3e-05,0.035,0.035,0.0088,0,0,0,0,0,0,0,0 -13490000,0.7,0.00085,-0.014,0.71,0.00055,0.0062,-0.019,0.0033,0.0018,-3.7e+02,-0.0011,-0.0059,-0.00045,0.00019,0.0015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8.2e-05,0.063,0.063,0.028,0.056,0.056,0.05,3.5e-05,3.5e-05,4.1e-05,0.035,0.035,0.0087,0,0,0,0,0,0,0,0 -13590000,0.7,0.0008,-0.014,0.71,0.00075,0.0064,-0.021,0.0023,0.0012,-3.7e+02,-0.0011,-0.0059,-0.00049,0.00018,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,8.2e-05,0.052,0.052,0.028,0.048,0.048,0.05,3.4e-05,3.4e-05,4e-05,0.035,0.035,0.0084,0,0,0,0,0,0,0,0 -13690000,0.7,0.00077,-0.014,0.71,0.0015,0.0083,-0.025,0.0024,0.0019,-3.7e+02,-0.0011,-0.0059,-0.00038,0.00021,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0002,0.0002,8e-05,0.059,0.059,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,3.8e-05,0.035,0.035,0.0083,0,0,0,0,0,0,0,0 -13790000,0.7,0.00066,-0.014,0.71,0.002,0.0041,-0.027,0.0034,-0.00048,-3.7e+02,-0.0011,-0.0059,-0.00037,6.1e-05,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.9e-05,0.05,0.05,0.029,0.048,0.048,0.049,3.2e-05,3.2e-05,3.7e-05,0.035,0.035,0.0079,0,0,0,0,0,0,0,0 -13890000,0.7,0.00063,-0.014,0.71,0.0026,0.0041,-0.031,0.0037,-9.1e-05,-3.7e+02,-0.0011,-0.0059,-0.0003,9.1e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.9e-05,0.056,0.056,0.03,0.056,0.056,0.05,3.2e-05,3.2e-05,3.5e-05,0.035,0.035,0.0078,0,0,0,0,0,0,0,0 -13990000,0.7,0.00056,-0.014,0.71,0.0028,0.0016,-0.03,0.0044,-0.0019,-3.7e+02,-0.0011,-0.006,-0.00028,-0.00013,0.0013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.7e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,3.4e-05,0.035,0.035,0.0074,0,0,0,0,0,0,0,0 -14090000,0.7,0.00054,-0.014,0.71,0.0029,0.0018,-0.031,0.0047,-0.0017,-3.7e+02,-0.0011,-0.006,-0.00017,-0.00012,0.0013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.6e-05,0.054,0.054,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,3.2e-05,0.035,0.035,0.0073,0,0,0,0,0,0,0,0 -14190000,0.7,0.00044,-0.014,0.71,0.0062,0.0012,-0.033,0.0067,-0.0015,-3.7e+02,-0.0011,-0.006,-0.00011,-0.00015,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.6e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,3.1e-05,0.035,0.035,0.0069,0,0,0,0,0,0,0,0 -14290000,0.7,0.00045,-0.014,0.71,0.0071,0.002,-0.032,0.0074,-0.0014,-3.7e+02,-0.0011,-0.006,-6.5e-05,-0.00022,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.5e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,3e-05,0.035,0.035,0.0067,0,0,0,0,0,0,0,0 -14390000,0.7,0.00036,-0.014,0.71,0.0088,0.0029,-0.034,0.0087,-0.0012,-3.7e+02,-0.001,-0.006,4.1e-05,-0.00026,0.00092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7.3e-05,0.044,0.044,0.031,0.047,0.047,0.05,2.8e-05,2.8e-05,2.9e-05,0.034,0.034,0.0063,0,0,0,0,0,0,0,0 -14490000,0.7,0.00035,-0.014,0.71,0.0089,0.0042,-0.037,0.0096,-0.00085,-3.7e+02,-0.001,-0.006,7e-05,-0.00021,0.00088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.2e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,2.8e-05,0.034,0.034,0.0062,0,0,0,0,0,0,0,0 -14590000,0.7,0.00034,-0.013,0.71,0.0054,0.0026,-0.037,0.006,-0.0023,-3.7e+02,-0.0011,-0.006,7.2e-05,-0.0005,0.0013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7.2e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,2.7e-05,0.034,0.034,0.0058,0,0,0,0,0,0,0,0 -14690000,0.7,0.0003,-0.013,0.71,0.0069,-0.00029,-0.034,0.0067,-0.0022,-3.7e+02,-0.0011,-0.006,0.00014,-0.0006,0.0014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,7.1e-05,0.048,0.048,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,2.6e-05,0.034,0.034,0.0056,0,0,0,0,0,0,0,0 -14790000,0.7,0.00032,-0.013,0.71,0.0036,-0.0019,-0.03,0.0038,-0.0032,-3.7e+02,-0.0011,-0.006,0.00016,-0.00093,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,7e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,2.5e-05,0.034,0.034,0.0053,0,0,0,0,0,0,0,0 -14890000,0.7,0.00031,-0.013,0.71,0.0052,-0.00087,-0.033,0.0042,-0.0034,-3.7e+02,-0.0011,-0.006,0.0002,-0.00091,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,6.9e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,2.4e-05,0.034,0.034,0.0051,0,0,0,0,0,0,0,0 -14990000,0.7,0.00031,-0.013,0.71,0.004,-0.0011,-0.029,0.0032,-0.0027,-3.7e+02,-0.0011,-0.006,0.00018,-0.00098,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.8e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,2.3e-05,0.034,0.034,0.0048,0,0,0,0,0,0,0,0 -15090000,0.7,0.00023,-0.013,0.71,0.0045,-0.0012,-0.032,0.0036,-0.0028,-3.7e+02,-0.0011,-0.006,0.00018,-0.00093,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00019,0.00019,6.8e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,2.3e-05,0.034,0.034,0.0046,0,0,0,0,0,0,0,0 -15190000,0.7,0.00025,-0.013,0.71,0.0038,-6.2e-05,-0.029,0.0029,-0.0023,-3.7e+02,-0.0011,-0.006,0.00017,-0.00096,0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.7e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,2.2e-05,0.034,0.034,0.0043,0,0,0,0,0,0,0,0 -15290000,0.7,0.00021,-0.013,0.71,0.0044,0.00018,-0.027,0.0033,-0.0023,-3.7e+02,-0.0011,-0.006,0.00021,-0.001,0.0022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.6e-05,0.045,0.045,0.03,0.053,0.053,0.052,2.2e-05,2.2e-05,2.1e-05,0.034,0.034,0.0042,0,0,0,0,0,0,0,0 -15390000,0.71,0.00021,-0.013,0.71,0.0037,0.00045,-0.024,0.00067,-0.0019,-3.7e+02,-0.0012,-0.006,0.0003,-0.0011,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.5e-05,0.039,0.039,0.029,0.047,0.047,0.051,2e-05,2e-05,2e-05,0.034,0.034,0.0039,0,0,0,0,0,0,0,0 -15490000,0.7,0.00023,-0.013,0.71,0.005,0.00015,-0.024,0.0011,-0.0019,-3.7e+02,-0.0012,-0.006,0.00025,-0.0011,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.5e-05,0.044,0.044,0.029,0.053,0.053,0.053,2e-05,2e-05,2e-05,0.034,0.034,0.0037,0,0,0,0,0,0,0,0 -15590000,0.7,0.00024,-0.013,0.71,0.003,7.8e-05,-0.023,-0.0012,-0.0016,-3.7e+02,-0.0012,-0.006,0.00022,-0.0011,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,1.9e-05,0.033,0.033,0.0035,0,0,0,0,0,0,0,0 -15690000,0.7,0.00025,-0.013,0.71,0.0034,-1.7e-05,-0.023,-0.00087,-0.0015,-3.7e+02,-0.0012,-0.006,0.00021,-0.0011,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.3e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,1.8e-05,0.033,0.033,0.0033,0,0,0,0,0,0,0,0 -15790000,0.7,0.00021,-0.013,0.71,0.0038,-0.0017,-0.026,-0.00083,-0.0026,-3.7e+02,-0.0012,-0.0061,0.00021,-0.0013,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.3e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,1.8e-05,0.033,0.033,0.0031,0,0,0,0,0,0,0,0 -15890000,0.7,0.00016,-0.013,0.71,0.0048,-0.0022,-0.024,-0.00037,-0.0029,-3.7e+02,-0.0012,-0.0061,0.00022,-0.0013,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00018,0.00018,6.2e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,1.7e-05,0.033,0.033,0.003,0,0,0,0,0,0,0,0 -15990000,0.71,0.0001,-0.013,0.71,0.0046,-0.0031,-0.019,-0.0005,-0.0037,-3.7e+02,-0.0012,-0.0061,0.00028,-0.0016,0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.1e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,1.7e-05,0.033,0.033,0.0028,0,0,0,0,0,0,0,0 -16090000,0.71,0.0001,-0.013,0.71,0.0064,-0.0033,-0.016,4.1e-05,-0.004,-3.7e+02,-0.0012,-0.0061,0.00036,-0.0017,0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6.1e-05,0.042,0.042,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,1.6e-05,0.033,0.033,0.0027,0,0,0,0,0,0,0,0 -16190000,0.71,0.00013,-0.013,0.71,0.0063,-0.0026,-0.014,-0.00022,-0.0033,-3.7e+02,-0.0012,-0.0061,0.00037,-0.0016,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00016,6e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,1.6e-05,0.033,0.033,0.0025,0,0,0,0,0,0,0,0 -16290000,0.71,0.00014,-0.013,0.71,0.008,-0.0033,-0.016,0.0005,-0.0036,-3.7e+02,-0.0012,-0.0061,0.00044,-0.0016,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00017,6e-05,0.042,0.042,0.024,0.052,0.052,0.052,1.5e-05,1.5e-05,1.5e-05,0.033,0.033,0.0024,0,0,0,0,0,0,0,0 -16390000,0.71,0.00013,-0.013,0.71,0.0068,-0.0036,-0.015,0.00012,-0.0029,-3.7e+02,-0.0012,-0.0061,0.00042,-0.0015,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.9e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,1.5e-05,0.032,0.032,0.0022,0,0,0,0,0,0,0,0 -16490000,0.71,0.00015,-0.013,0.71,0.0061,-0.0031,-0.018,0.00074,-0.0032,-3.7e+02,-0.0012,-0.0061,0.00043,-0.0014,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00017,0.00016,5.9e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,1.4e-05,0.032,0.032,0.0021,0,0,0,0,0,0,0,0 -16590000,0.71,0.0004,-0.013,0.71,0.0025,-0.00048,-0.018,-0.0023,0.00012,-3.7e+02,-0.0013,-0.006,0.00044,-0.00074,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.8e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,1.4e-05,0.032,0.032,0.002,0,0,0,0,0,0,0,0 -16690000,0.71,0.00039,-0.013,0.71,0.0027,4.3e-05,-0.015,-0.002,0.0001,-3.7e+02,-0.0013,-0.006,0.0004,-0.0008,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,1.4e-05,0.032,0.032,0.0019,0,0,0,0,0,0,0,0 -16790000,0.71,0.00054,-0.013,0.71,-0.00072,0.0022,-0.014,-0.0044,0.0027,-3.7e+02,-0.0013,-0.006,0.00041,-0.00021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,1.3e-05,0.032,0.032,0.0018,0,0,0,0,0,0,0,0 -16890000,0.71,0.00056,-0.013,0.71,-0.00095,0.0031,-0.011,-0.0045,0.003,-3.7e+02,-0.0013,-0.006,0.00039,-0.00025,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00016,0.00016,5.6e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,1.3e-05,0.032,0.032,0.0017,0,0,0,0,0,0,0,0 -16990000,0.71,0.0005,-0.013,0.71,-0.00098,0.001,-0.01,-0.005,0.0011,-3.7e+02,-0.0013,-0.006,0.00035,-0.00065,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.6e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,1.2e-05,0.032,0.032,0.0016,0,0,0,0,0,0,0,0 -17090000,0.71,0.00046,-0.013,0.71,-0.00014,0.002,-0.01,-0.0051,0.0012,-3.7e+02,-0.0013,-0.006,0.00035,-0.00064,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.5e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,1.2e-05,0.032,0.032,0.0016,0,0,0,0,0,0,0,0 -17190000,0.71,0.00045,-0.013,0.71,0.00024,0.0019,-0.011,-0.0054,-0.00032,-3.7e+02,-0.0013,-0.006,0.00038,-0.00099,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.5e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,1.2e-05,0.031,0.031,0.0015,0,0,0,0,0,0,0,0 -17290000,0.71,0.00043,-0.013,0.71,0.0024,0.003,-0.0066,-0.0053,-9.1e-05,-3.7e+02,-0.0013,-0.006,0.00034,-0.001,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00015,0.00015,5.4e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,1.2e-05,0.031,0.031,0.0014,0,0,0,0,0,0,0,0 -17390000,0.71,0.00039,-0.013,0.71,0.003,0.0021,-0.0047,-0.0045,-0.0014,-3.7e+02,-0.0013,-0.006,0.00038,-0.0014,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.4e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,1.1e-05,0.031,0.031,0.0013,0,0,0,0,0,0,0,0 -17490000,0.71,0.00039,-0.013,0.71,0.0035,0.0017,-0.003,-0.0042,-0.0012,-3.7e+02,-0.0013,-0.006,0.00038,-0.0014,0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,1.1e-05,0.031,0.031,0.0013,0,0,0,0,0,0,0,0 -17590000,0.71,0.0003,-0.013,0.71,0.0047,0.0005,0.0025,-0.0035,-0.0024,-3.7e+02,-0.0013,-0.0061,0.00039,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,1.1e-05,0.031,0.031,0.0012,0,0,0,0,0,0,0,0 -17690000,0.71,0.00027,-0.013,0.71,0.0057,0.0013,0.0019,-0.003,-0.0023,-3.7e+02,-0.0013,-0.0061,0.00041,-0.0017,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.2e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,1e-05,0.031,0.031,0.0012,0,0,0,0,0,0,0,0 -17790000,0.71,0.00018,-0.013,0.71,0.0082,0.0009,0.00059,-0.0019,-0.002,-3.7e+02,-0.0013,-0.0061,0.00048,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.2e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,1e-05,0.031,0.031,0.0011,0,0,0,0,0,0,0,0 -17890000,0.71,0.00019,-0.013,0.71,0.0097,0.00018,0.00069,-0.00099,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00051,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00014,0.00014,5.2e-05,0.037,0.037,0.016,0.051,0.051,0.048,7e-06,7e-06,9.8e-06,0.031,0.031,0.0011,0,0,0,0,0,0,0,0 -17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0016,0.0019,-0.00034,-0.0017,-3.7e+02,-0.0013,-0.0061,0.0005,-0.0017,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.1e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,9.6e-06,0.03,0.03,0.001,0,0,0,0,0,0,0,0 -18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0018,0.0043,0.00083,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00045,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5.1e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,9.3e-06,0.03,0.03,0.00097,0,0,0,0,0,0,0,0 -18190000,0.71,0.0001,-0.013,0.71,0.013,-0.00074,0.0056,0.0016,-0.0015,-3.7e+02,-0.0013,-0.006,0.00048,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,9.1e-06,0.03,0.03,0.00092,0,0,0,0,0,0,0,0 -18290000,0.71,4.6e-05,-0.013,0.71,0.013,-0.0013,0.0068,0.0029,-0.0016,-3.7e+02,-0.0013,-0.006,0.00046,-0.0017,0.0052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,5e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,8.9e-06,0.03,0.03,0.00089,0,0,0,0,0,0,0,0 -18390000,0.71,6.1e-05,-0.013,0.71,0.014,0.00032,0.008,0.0034,-0.0012,-3.7e+02,-0.0013,-0.006,0.00049,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.9e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,8.6e-06,0.03,0.03,0.00084,0,0,0,0,0,0,0,0 -18490000,0.71,7.6e-05,-0.013,0.71,0.015,0.00077,0.0076,0.0049,-0.0011,-3.7e+02,-0.0013,-0.006,0.0005,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00013,0.00013,4.9e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,8.5e-06,0.03,0.03,0.00082,0,0,0,0,0,0,0,0 -18590000,0.71,8.1e-05,-0.012,0.71,0.014,0.00095,0.0058,0.0037,-0.00098,-3.7e+02,-0.0013,-0.006,0.00054,-0.0016,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.9e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,8.2e-06,0.03,0.03,0.00078,0,0,0,0,0,0,0,0 -18690000,0.71,5e-05,-0.012,0.71,0.014,0.00029,0.0039,0.0051,-0.00089,-3.7e+02,-0.0013,-0.006,0.00053,-0.0016,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.8e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,8e-06,0.03,0.03,0.00075,0,0,0,0,0,0,0,0 -18790000,0.71,8.1e-05,-0.012,0.71,0.013,0.00054,0.0035,0.0039,-0.00071,-3.7e+02,-0.0014,-0.006,0.00051,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.8e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,7.9e-06,0.03,0.03,0.00072,0,0,0,0,0,0,0,0 -18890000,0.71,0.0001,-0.012,0.71,0.013,0.0011,0.0042,0.0052,-0.0006,-3.7e+02,-0.0014,-0.006,0.00056,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,7.7e-06,0.03,0.03,0.0007,0,0,0,0,0,0,0,0 -18990000,0.71,9.1e-05,-0.012,0.71,0.014,0.0019,0.0028,0.0065,-0.00051,-3.7e+02,-0.0014,-0.006,0.00057,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,7.5e-06,0.029,0.029,0.00066,0,0,0,0,0,0,0,0 -19090000,0.71,7.5e-05,-0.012,0.71,0.015,0.0025,0.0058,0.008,-0.00026,-3.7e+02,-0.0014,-0.006,0.00057,-0.0016,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00012,0.00012,4.7e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,7.3e-06,0.029,0.03,0.00065,0,0,0,0,0,0,0,0 -19190000,0.71,7.7e-05,-0.012,0.71,0.015,0.0025,0.0059,0.0087,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00059,-0.0017,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,7.2e-06,0.029,0.029,0.00062,0,0,0,0,0,0,0,0 -19290000,0.71,0.0001,-0.012,0.71,0.015,0.0018,0.0086,0.01,-2.8e-05,-3.7e+02,-0.0014,-0.0061,0.00056,-0.0017,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,7e-06,0.029,0.029,0.0006,0,0,0,0,0,0,0,0 -19390000,0.71,0.00011,-0.012,0.71,0.013,0.0008,0.012,0.0082,-9.1e-05,-3.7e+02,-0.0014,-0.0061,0.00058,-0.0017,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.6e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,6.8e-06,0.029,0.029,0.00058,0,0,0,0,0,0,0,0 -19490000,0.71,0.00014,-0.012,0.71,0.012,0.00011,0.0088,0.0094,-4.9e-05,-3.7e+02,-0.0014,-0.0061,0.00061,-0.0017,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,6.7e-06,0.029,0.029,0.00056,0,0,0,0,0,0,0,0 -19590000,0.71,0.00018,-0.012,0.71,0.01,-0.00096,0.0081,0.0076,-0.00011,-3.7e+02,-0.0014,-0.0061,0.00065,-0.0017,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,6.5e-06,0.029,0.029,0.00054,0,0,0,0,0,0,0,0 -19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0031,0.0096,0.0086,-0.00032,-3.7e+02,-0.0014,-0.0061,0.00063,-0.0017,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.5e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,6.4e-06,0.029,0.029,0.00052,0,0,0,0,0,0,0,0 -19790000,0.71,0.00025,-0.012,0.71,0.008,-0.004,0.01,0.007,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00063,-0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.4e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,6.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19890000,0.71,0.0002,-0.012,0.71,0.0068,-0.0043,0.011,0.0077,-0.00069,-3.7e+02,-0.0014,-0.0061,0.00067,-0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.00011,4.4e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,6.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19990000,0.71,0.00019,-0.012,0.71,0.0043,-0.005,0.014,0.0063,-0.00058,-3.7e+02,-0.0014,-0.006,0.00073,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.4e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20090000,0.71,0.00018,-0.012,0.71,0.0041,-0.0069,0.014,0.0067,-0.0012,-3.7e+02,-0.0014,-0.006,0.00078,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.00011,0.0001,4.4e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,5.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20190000,0.71,0.00028,-0.012,0.71,0.0018,-0.0076,0.017,0.0044,-0.00092,-3.7e+02,-0.0014,-0.006,0.0008,-0.0015,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,5.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20290000,0.71,0.00024,-0.012,0.71,0.00064,-0.0092,0.015,0.0045,-0.0018,-3.7e+02,-0.0014,-0.006,0.00081,-0.0015,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,5.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20390000,0.71,0.00026,-0.012,0.71,-0.0019,-0.0098,0.017,0.0026,-0.0014,-3.7e+02,-0.0014,-0.006,0.00081,-0.0013,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.3e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,5.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20490000,0.71,0.00032,-0.012,0.71,-0.0023,-0.011,0.016,0.0024,-0.0024,-3.7e+02,-0.0014,-0.006,0.00079,-0.0013,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,5.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20590000,0.71,0.00034,-0.012,0.71,-0.002,-0.011,0.013,0.002,-0.0019,-3.7e+02,-0.0014,-0.006,0.00077,-0.0011,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.9e-05,9.9e-05,4.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,5.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20690000,0.71,0.00037,-0.012,0.71,-0.002,-0.012,0.015,0.0018,-0.003,-3.7e+02,-0.0014,-0.006,0.00078,-0.0011,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,0.0001,0.0001,4.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,5.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20790000,0.71,0.00039,-0.012,0.71,-0.0031,-0.011,0.015,0.0015,-0.0024,-3.7e+02,-0.0014,-0.006,0.00078,-0.00095,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.8e-05,9.7e-05,4.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,5.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20890000,0.71,0.00038,-0.012,0.71,-0.0035,-0.013,0.014,0.0012,-0.0036,-3.7e+02,-0.0014,-0.006,0.00081,-0.00096,0.0076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.8e-05,9.8e-05,4.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20990000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.015,0.0028,-0.003,-3.7e+02,-0.0014,-0.006,0.00081,-0.00076,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.6e-05,9.6e-05,4.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,4.9e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21090000,0.71,0.00038,-0.012,0.71,-0.0039,-0.017,0.015,0.0024,-0.0045,-3.7e+02,-0.0014,-0.006,0.00082,-0.00076,0.0074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.7e-05,9.7e-05,4.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,4.8e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21190000,0.71,0.00042,-0.012,0.71,-0.0032,-0.015,0.014,0.0039,-0.0036,-3.7e+02,-0.0014,-0.006,0.00081,-0.00053,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.5e-05,9.5e-05,4e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,4.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21290000,0.71,0.00046,-0.012,0.71,-0.0037,-0.018,0.016,0.0035,-0.0053,-3.7e+02,-0.0014,-0.006,0.00084,-0.00053,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.6e-05,9.5e-05,4e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,4.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21390000,0.71,0.0005,-0.012,0.71,-0.0046,-0.017,0.016,0.003,-0.0033,-3.7e+02,-0.0014,-0.006,0.00082,-0.00016,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.4e-05,9.4e-05,4e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,4.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21490000,0.71,0.00051,-0.012,0.71,-0.0051,-0.018,0.015,0.0025,-0.005,-3.7e+02,-0.0014,-0.006,0.00083,-0.00016,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.4e-05,9.4e-05,4e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,4.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21590000,0.71,0.00053,-0.012,0.71,-0.0056,-0.015,0.015,0.002,-0.003,-3.7e+02,-0.0014,-0.006,0.00082,0.00018,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.3e-05,9.3e-05,3.9e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,4.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21690000,0.71,0.00054,-0.012,0.71,-0.0055,-0.016,0.017,0.0015,-0.0046,-3.7e+02,-0.0014,-0.006,0.00083,0.00018,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.3e-05,9.3e-05,3.9e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,4.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21790000,0.71,0.00056,-0.012,0.71,-0.0061,-0.011,0.015,0.00019,-0.00063,-3.7e+02,-0.0014,-0.0059,0.0008,0.00071,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.2e-05,9.2e-05,3.9e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.2e-06,4.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21890000,0.71,0.00056,-0.012,0.71,-0.0061,-0.012,0.016,-0.00042,-0.0018,-3.7e+02,-0.0014,-0.0059,0.0008,0.0007,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.2e-05,9.2e-05,3.9e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,4.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21990000,0.71,0.00061,-0.012,0.71,-0.0066,-0.0089,0.016,-0.0014,0.0016,-3.7e+02,-0.0014,-0.0059,0.00079,0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.1e-05,9.1e-05,3.9e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22090000,0.71,0.00063,-0.012,0.71,-0.0069,-0.008,0.015,-0.002,0.00076,-3.7e+02,-0.0014,-0.0059,0.00078,0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9.1e-05,9.1e-05,3.8e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22190000,0.71,0.0006,-0.012,0.71,-0.0068,-0.0072,0.015,-0.0017,0.0007,-3.7e+02,-0.0014,-0.0059,0.00078,0.0012,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,9e-05,3.8e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,3.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22290000,0.71,0.00064,-0.012,0.71,-0.0081,-0.0079,0.015,-0.0024,-6.3e-05,-3.7e+02,-0.0014,-0.0059,0.00077,0.0012,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,9e-05,3.8e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,3.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22390000,0.71,0.00061,-0.012,0.71,-0.0087,-0.0074,0.017,-0.0021,-7.2e-05,-3.7e+02,-0.0014,-0.0059,0.00077,0.0013,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.9e-05,8.9e-05,3.8e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22490000,0.71,0.00062,-0.012,0.71,-0.0093,-0.0073,0.018,-0.003,-0.00083,-3.7e+02,-0.0014,-0.0059,0.00077,0.0013,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,9e-05,8.9e-05,3.7e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22590000,0.71,0.0006,-0.012,0.71,-0.0091,-0.0068,0.017,-0.0033,0.00024,-3.7e+02,-0.0014,-0.0059,0.00076,0.0014,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.7e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,3.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22690000,0.71,0.00063,-0.012,0.71,-0.01,-0.0066,0.018,-0.0042,-0.00043,-3.7e+02,-0.0014,-0.0059,0.00077,0.0014,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.9e-05,8.9e-05,3.7e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,3.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0054,0.019,-0.0054,-0.00034,-3.7e+02,-0.0014,-0.0059,0.00073,0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.7e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,3.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.005,0.021,-0.0065,-0.00086,-3.7e+02,-0.0014,-0.0059,0.00072,0.0015,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.8e-05,3.6e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,3.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0055,0.022,-0.0073,-0.00077,-3.7e+02,-0.0014,-0.0059,0.00073,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.7e-05,3.6e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,3.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23090000,0.71,0.00057,-0.012,0.71,-0.013,-0.0055,0.022,-0.0086,-0.0013,-3.7e+02,-0.0014,-0.0059,0.0007,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.8e-05,8.7e-05,3.6e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,3.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23190000,0.71,0.00064,-0.012,0.71,-0.014,-0.0064,0.024,-0.012,-0.0012,-3.7e+02,-0.0014,-0.0059,0.00069,0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.6e-05,3.6e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,3.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0077,0.024,-0.013,-0.0019,-3.7e+02,-0.0014,-0.0059,0.00069,0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.7e-05,3.6e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,3.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.0079,0.022,-0.016,-0.0017,-3.7e+02,-0.0014,-0.0059,0.00069,0.0017,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.6e-05,8.6e-05,3.5e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,3.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0088,-0.012,-0.018,-0.0025,-3.7e+02,-0.0014,-0.0059,0.00069,0.0017,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0038,8.7e-05,8.6e-05,3.5e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,3.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23590000,0.71,0.0083,-0.0018,0.71,-0.033,-0.0075,-0.044,-0.016,-0.0012,-3.7e+02,-0.0014,-0.0059,0.00068,0.0019,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.7e-05,8.5e-05,3.5e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0023,-3.7e+02,-0.0014,-0.0059,0.00067,0.0019,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.8e-05,8.5e-05,3.5e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23790000,0.71,0.005,0.00064,0.71,-0.088,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-0.0014,-0.0059,0.00068,0.0021,0.0064,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.6e-05,8.4e-05,3.5e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,2.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.0049,-3.7e+02,-0.0014,-0.0059,0.00067,0.0021,0.0064,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.6e-05,8.5e-05,3.4e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,2.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.039,-0.25,-0.034,-0.0081,-3.7e+02,-0.0014,-0.0059,0.00067,0.0022,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.4e-05,3.4e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,2.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,0.00068,0.0022,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.5e-05,8.4e-05,3.4e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-07,6.7e-07,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,0.00068,0.0024,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.4e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-07,6.4e-07,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-0.0014,-0.0059,0.00067,0.0024,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.5e-05,8.4e-05,3.4e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.4e-07,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24390000,0.71,0.0038,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0013,-0.0059,0.00065,0.0021,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-0.0013,-0.0059,0.00065,0.0021,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.3e-05,3.3e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24590000,0.71,0.0051,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,0.00066,0.002,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,0.00067,0.002,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.3e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,0.00065,0.0024,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.3e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24890000,0.71,0.0066,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,0.00064,0.0024,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,8.2e-05,3.2e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24990000,0.71,0.0084,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,0.00063,0.0032,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25090000,0.71,0.0087,0.0041,0.71,-0.27,-0.13,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,0.00061,0.0033,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8.1e-05,3.2e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,0.00062,0.0029,0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.2e-05,8e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.3e-07,5.2e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,0.00062,0.0029,0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,8e-05,3.2e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,0.00062,0.003,-4.5e-06,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.3e-05,7.9e-05,3.2e-05,0.017,0.016,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,0.00063,0.003,5.6e-06,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0037,8.4e-05,7.9e-05,3.2e-05,0.019,0.018,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,0.00063,0.0027,-0.00089,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.2e-05,7.8e-05,3.1e-05,0.017,0.016,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,0.00064,0.0027,-0.00087,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.4e-05,7.9e-05,3.1e-05,0.019,0.018,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,0.00065,0.0034,-0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.4e-05,7.8e-05,3.1e-05,0.018,0.016,0.0079,0.04,0.04,0.035,4.8e-07,4.7e-07,2.2e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25890000,0.7,0.017,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,0.00067,0.0034,-0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0036,8.5e-05,7.8e-05,3.1e-05,0.02,0.018,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,2.1e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25990000,0.7,0.016,0.025,0.71,-0.65,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,0.00068,0.003,-0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0035,8.2e-05,7.7e-05,3.1e-05,0.019,0.017,0.0079,0.04,0.04,0.035,4.7e-07,4.6e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,0.00067,0.003,-0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0035,8.5e-05,7.7e-05,3.1e-05,0.021,0.018,0.008,0.044,0.044,0.035,4.7e-07,4.6e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26190000,0.7,0.023,0.045,0.71,-0.77,-0.4,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,0.00068,0.0042,-0.0085,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0034,8.6e-05,7.7e-05,3e-05,0.02,0.017,0.0079,0.04,0.04,0.035,4.6e-07,4.5e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26290000,0.7,0.024,0.047,0.71,-0.86,-0.44,-1.3,-0.61,-0.47,-3.7e+02,-0.0011,-0.0059,0.00068,0.0042,-0.0085,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0034,8.7e-05,7.7e-05,3e-05,0.023,0.018,0.008,0.044,0.044,0.035,4.6e-07,4.5e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26390000,0.7,0.023,0.044,0.71,-0.94,-0.5,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,0.0007,0.0029,-0.0098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0033,8.4e-05,7.6e-05,3e-05,0.022,0.017,0.0079,0.04,0.04,0.035,4.5e-07,4.4e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26490000,0.7,0.03,0.059,0.71,-1,-0.54,-1.3,-0.77,-0.6,-3.7e+02,-0.001,-0.0059,0.00071,0.0029,-0.0098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0033,9.1e-05,7.6e-05,3e-05,0.025,0.019,0.008,0.045,0.044,0.035,4.5e-07,4.4e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26590000,0.7,0.036,0.075,0.71,-1.1,-0.6,-1.3,-0.82,-0.67,-3.7e+02,-0.00097,-0.0059,0.00069,0.004,-0.013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0031,9.5e-05,7.6e-05,3e-05,0.024,0.017,0.008,0.04,0.039,0.035,4.4e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26690000,0.7,0.037,0.078,0.71,-1.3,-0.66,-1.3,-0.94,-0.73,-3.7e+02,-0.00097,-0.0059,0.00072,0.0039,-0.013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0031,9.7e-05,7.6e-05,3e-05,0.029,0.019,0.008,0.045,0.044,0.035,4.4e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26790000,0.7,0.035,0.073,0.71,-1.4,-0.75,-1.3,-1,-0.86,-3.7e+02,-0.00093,-0.006,0.00073,0.0019,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0029,9.1e-05,7.5e-05,3e-05,0.028,0.018,0.008,0.041,0.039,0.035,4.4e-07,4.2e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26890000,0.7,0.044,0.095,0.71,-1.5,-0.81,-1.3,-1.2,-0.94,-3.7e+02,-0.00093,-0.006,0.00076,0.0018,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.0001,7.6e-05,3e-05,0.033,0.021,0.0081,0.046,0.044,0.035,4.4e-07,4.2e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26990000,0.69,0.049,0.12,0.71,-1.6,-0.91,-1.3,-1.2,-1,-3.7e+02,-0.00085,-0.0059,0.00079,0.0032,-0.019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,0.00011,7.7e-05,3e-05,0.032,0.02,0.0081,0.041,0.04,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27090000,0.69,0.05,0.12,0.71,-1.8,-1,-1.3,-1.4,-1.1,-3.7e+02,-0.00084,-0.0059,0.00083,0.0031,-0.02,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.00011,7.7e-05,3e-05,0.039,0.022,0.0082,0.046,0.044,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27190000,0.7,0.047,0.11,0.71,-2.1,-1.1,-1.2,-1.6,-1.2,-3.7e+02,-0.00083,-0.0059,0.00087,0.004,-0.02,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.8e-05,7.6e-05,3e-05,0.04,0.023,0.0082,0.049,0.046,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27290000,0.7,0.042,0.094,0.71,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00083,-0.0059,0.0009,0.0039,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,9.2e-05,7.5e-05,3e-05,0.046,0.025,0.0082,0.056,0.051,0.035,4.3e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27390000,0.7,0.036,0.078,0.71,-2.3,-1.2,-1.2,-2,-1.4,-3.7e+02,-0.00079,-0.0058,0.00095,0.0063,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0021,8.3e-05,7.4e-05,2.9e-05,0.043,0.025,0.0082,0.057,0.054,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27490000,0.7,0.03,0.063,0.71,-2.4,-1.2,-1.2,-2.2,-1.5,-3.7e+02,-0.00078,-0.0058,0.00098,0.0062,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0021,8e-05,7.4e-05,2.9e-05,0.047,0.027,0.0083,0.065,0.059,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27590000,0.7,0.026,0.05,0.71,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-0.00077,-0.0058,0.001,0.0056,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0018,7.7e-05,7.4e-05,2.9e-05,0.041,0.025,0.0082,0.067,0.062,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27690000,0.7,0.025,0.049,0.71,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00077,-0.0058,0.001,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0018,7.6e-05,7.4e-05,2.9e-05,0.043,0.027,0.0083,0.075,0.068,0.035,4.3e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27790000,0.71,0.026,0.05,0.71,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-0.00076,-0.0058,0.001,0.0055,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0016,7.6e-05,7.4e-05,2.8e-05,0.038,0.026,0.0083,0.076,0.07,0.035,4.3e-07,4e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27890000,0.71,0.025,0.048,0.71,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-0.00076,-0.0058,0.001,0.0053,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0016,7.6e-05,7.4e-05,2.8e-05,0.04,0.028,0.0084,0.085,0.077,0.036,4.3e-07,4e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27990000,0.71,0.024,0.044,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-0.00076,-0.0058,0.001,0.0044,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,7.5e-05,7.4e-05,2.8e-05,0.035,0.026,0.0083,0.085,0.079,0.035,4.3e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-0.00076,-0.0058,0.00097,0.0044,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0014,7.6e-05,7.4e-05,2.8e-05,0.037,0.028,0.0084,0.095,0.087,0.035,4.3e-07,4e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-0.00076,-0.0058,0.00096,0.0039,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,7.3e-05,2.8e-05,0.033,0.026,0.0084,0.095,0.088,0.035,4.3e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28290000,0.71,0.027,0.054,0.7,-2.8,-1.3,-0.087,-4.5,-2.4,-3.7e+02,-0.00076,-0.0058,0.00093,0.0038,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.5e-05,7.4e-05,2.8e-05,0.034,0.027,0.0086,0.1,0.096,0.036,4.3e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28390000,0.71,0.011,0.022,0.7,-2.8,-1.3,0.77,-4.8,-2.6,-3.7e+02,-0.00076,-0.0058,0.00091,0.0035,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.5e-05,7.4e-05,2.8e-05,0.035,0.028,0.0087,0.11,0.1,0.036,4.3e-07,3.9e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28490000,0.71,0.0021,0.0042,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-0.00076,-0.0058,0.00089,0.0033,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,7.5e-05,2.7e-05,0.035,0.029,0.0088,0.13,0.11,0.036,4.3e-07,3.9e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28590000,0.71,0.00035,0.00071,0.7,-2.7,-1.3,0.96,-5.3,-2.8,-3.7e+02,-0.00076,-0.0058,0.00088,0.003,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.5e-05,2.7e-05,0.035,0.03,0.0089,0.14,0.12,0.036,4.4e-07,4e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28690000,0.71,-0.00036,-0.00021,0.7,-2.6,-1.2,0.97,-5.6,-2.9,-3.7e+02,-0.00076,-0.0058,0.00087,0.0026,-0.015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.5e-05,2.7e-05,0.035,0.032,0.009,0.15,0.13,0.036,4.4e-07,4e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28790000,0.71,-0.00085,-0.00057,0.7,-2.6,-1.2,0.97,-5.9,-3,-3.7e+02,-0.00078,-0.0058,0.00084,-0.00053,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.5e-05,2.7e-05,0.031,0.029,0.0089,0.15,0.13,0.036,4.3e-07,3.9e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28890000,0.71,-0.00087,-0.00036,0.7,-2.5,-1.2,0.96,-6.2,-3.1,-3.7e+02,-0.00078,-0.0058,0.00082,-0.00091,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.5e-05,2.7e-05,0.031,0.03,0.009,0.16,0.14,0.036,4.4e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28990000,0.72,-0.00085,-1.5e-05,0.7,-2.5,-1.2,0.95,-6.5,-3.2,-3.7e+02,-0.00082,-0.0058,0.00077,-0.0026,-0.029,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.5e-05,2.7e-05,0.028,0.028,0.009,0.16,0.14,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29090000,0.72,-0.0007,0.00037,0.7,-2.4,-1.1,0.94,-6.8,-3.4,-3.7e+02,-0.00082,-0.0058,0.00074,-0.003,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.7e-05,0.029,0.029,0.009,0.17,0.15,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29190000,0.72,-0.00056,0.00074,0.7,-2.4,-1.1,0.94,-7.1,-3.5,-3.7e+02,-0.00085,-0.0058,0.00071,-0.0043,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.7e-05,0.027,0.028,0.009,0.17,0.15,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29290000,0.72,-0.0002,0.0016,0.7,-2.3,-1.1,0.96,-7.3,-3.6,-3.7e+02,-0.00085,-0.0058,0.00067,-0.0048,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.8e-05,7.6e-05,2.6e-05,0.027,0.029,0.0091,0.18,0.16,0.036,4.3e-07,3.9e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29390000,0.72,0.0003,0.003,0.7,-2.3,-1.1,0.97,-7.6,-3.7,-3.7e+02,-0.00089,-0.0058,0.00061,-0.0055,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.025,0.027,0.009,0.17,0.16,0.036,4.3e-07,3.8e-07,1.4e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -29490000,0.72,0.00082,0.0041,0.7,-2.3,-1.1,0.97,-7.9,-3.8,-3.7e+02,-0.00089,-0.0058,0.00058,-0.0059,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.026,0.028,0.0091,0.19,0.17,0.037,4.3e-07,3.8e-07,1.4e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -29590000,0.72,0.0012,0.0052,0.7,-2.2,-1.1,0.96,-8.1,-3.9,-3.7e+02,-0.00092,-0.0058,0.00054,-0.0076,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.8e-05,7.6e-05,2.6e-05,0.025,0.027,0.009,0.18,0.17,0.036,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -29690000,0.72,0.0015,0.0058,0.7,-2.2,-1.1,0.95,-8.3,-4,-3.7e+02,-0.00092,-0.0058,0.0005,-0.008,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.028,0.0091,0.2,0.18,0.036,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -29790000,0.72,0.0018,0.0063,0.7,-2.2,-1.1,0.94,-8.6,-4.1,-3.7e+02,-0.00095,-0.0058,0.00047,-0.009,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.025,0.026,0.0091,0.19,0.18,0.037,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -29890000,0.72,0.0018,0.0065,0.7,-2.1,-1.1,0.93,-8.8,-4.2,-3.7e+02,-0.00095,-0.0058,0.00042,-0.0097,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.21,0.19,0.037,4.2e-07,3.8e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -29990000,0.72,0.002,0.0067,0.7,-2.1,-1,0.91,-9.1,-4.3,-3.7e+02,-0.00098,-0.0058,0.00038,-0.011,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.025,0.026,0.009,0.2,0.19,0.036,4.1e-07,3.7e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30090000,0.72,0.002,0.0066,0.7,-2.1,-1,0.89,-9.3,-4.4,-3.7e+02,-0.00098,-0.0058,0.00034,-0.012,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.22,0.2,0.036,4.1e-07,3.7e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30190000,0.72,0.002,0.0065,0.7,-2.1,-1,0.88,-9.6,-4.5,-3.7e+02,-0.001,-0.0058,0.00031,-0.013,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.5e-05,2.6e-05,0.025,0.026,0.009,0.21,0.2,0.037,4.1e-07,3.7e-07,1.3e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30290000,0.72,0.0019,0.0063,0.7,-2,-1,0.87,-9.8,-4.6,-3.7e+02,-0.001,-0.0058,0.00027,-0.013,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.6e-05,2.6e-05,0.026,0.027,0.0091,0.22,0.21,0.037,4.1e-07,3.7e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30390000,0.72,0.0019,0.0061,0.7,-2,-1,0.85,-10,-4.7,-3.7e+02,-0.001,-0.0058,0.00023,-0.014,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.6e-05,0.025,0.026,0.009,0.22,0.21,0.036,4e-07,3.7e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30490000,0.72,0.0018,0.0059,0.7,-2,-1,0.84,-10,-4.8,-3.7e+02,-0.001,-0.0058,0.00021,-0.014,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.6e-05,0.026,0.027,0.0091,0.23,0.22,0.037,4e-07,3.7e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30590000,0.72,0.0018,0.0056,0.7,-1.9,-1,0.8,-10,-4.9,-3.7e+02,-0.0011,-0.0058,0.00018,-0.015,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.025,0.025,0.009,0.23,0.22,0.037,4e-07,3.6e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30690000,0.72,0.0016,0.0052,0.7,-1.9,-1,0.79,-11,-5,-3.7e+02,-0.0011,-0.0058,0.00015,-0.015,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.027,0.027,0.009,0.24,0.23,0.037,4e-07,3.6e-07,1.2e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -30790000,0.72,0.0016,0.0049,0.7,-1.9,-0.99,0.78,-11,-5.1,-3.7e+02,-0.0011,-0.0058,0.00011,-0.016,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.026,0.025,0.0089,0.24,0.23,0.037,3.9e-07,3.6e-07,1.2e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -30890000,0.72,0.0014,0.0045,0.7,-1.9,-0.98,0.77,-11,-5.2,-3.7e+02,-0.0011,-0.0058,8.4e-05,-0.016,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.027,0.027,0.009,0.25,0.24,0.037,3.9e-07,3.6e-07,1.2e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -30990000,0.72,0.0014,0.004,0.7,-1.8,-0.97,0.76,-11,-5.3,-3.7e+02,-0.0011,-0.0058,5e-05,-0.016,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8e-05,7.5e-05,2.5e-05,0.026,0.025,0.0089,0.25,0.24,0.036,3.8e-07,3.6e-07,1.2e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31090000,0.72,0.0012,0.0035,0.7,-1.8,-0.96,0.75,-11,-5.4,-3.7e+02,-0.0011,-0.0058,2.1e-05,-0.017,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.027,0.026,0.0089,0.26,0.25,0.037,3.8e-07,3.6e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31190000,0.72,0.0012,0.0033,0.7,-1.8,-0.96,0.74,-12,-5.4,-3.7e+02,-0.0011,-0.0058,-8e-06,-0.018,-0.017,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.026,0.025,0.0088,0.26,0.25,0.037,3.8e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31290000,0.72,0.00094,0.0027,0.7,-1.8,-0.95,0.74,-12,-5.5,-3.7e+02,-0.0011,-0.0058,-3.2e-05,-0.019,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.5e-05,2.5e-05,0.028,0.026,0.0089,0.27,0.26,0.037,3.8e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31390000,0.72,0.00087,0.0023,0.7,-1.7,-0.94,0.73,-12,-5.6,-3.7e+02,-0.0012,-0.0058,-6.1e-05,-0.019,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.026,0.025,0.0087,0.27,0.26,0.036,3.7e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31490000,0.72,0.00065,0.0016,0.7,-1.7,-0.93,0.73,-12,-5.7,-3.7e+02,-0.0012,-0.0058,-9.1e-05,-0.02,-0.013,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.028,0.026,0.0088,0.28,0.27,0.037,3.7e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31590000,0.72,0.00064,0.0013,0.7,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-0.0012,-0.0057,-0.00011,-0.02,-0.011,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.5e-05,0.027,0.025,0.0087,0.28,0.27,0.037,3.6e-07,3.4e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31690000,0.72,0.00038,0.00063,0.7,-1.6,-0.91,0.73,-13,-5.9,-3.7e+02,-0.0012,-0.0057,-0.00013,-0.021,-0.01,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.028,0.026,0.0087,0.29,0.28,0.037,3.6e-07,3.5e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31790000,0.71,0.00026,2.7e-05,0.7,-1.6,-0.9,0.73,-13,-6,-3.7e+02,-0.0012,-0.0057,-0.00015,-0.022,-0.0082,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.027,0.025,0.0087,0.29,0.27,0.037,3.5e-07,3.4e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31890000,0.71,7.3e-06,-0.00068,0.7,-1.6,-0.89,0.72,-13,-6.1,-3.7e+02,-0.0012,-0.0057,-0.00017,-0.022,-0.007,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.0011,8.1e-05,7.4e-05,2.4e-05,0.029,0.026,0.0087,0.3,0.29,0.037,3.5e-07,3.4e-07,1.1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -31990000,0.71,-7.7e-05,-0.0011,0.7,-1.6,-0.88,0.71,-13,-6.2,-3.7e+02,-0.0012,-0.0057,-0.0002,-0.023,-0.0052,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.027,0.025,0.0086,0.3,0.28,0.036,3.5e-07,3.4e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -32090000,0.71,-0.00037,-0.0019,0.7,-1.5,-0.87,0.72,-13,-6.2,-3.7e+02,-0.0012,-0.0057,-0.00022,-0.024,-0.0037,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.029,0.026,0.0087,0.31,0.3,0.037,3.5e-07,3.4e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -32190000,0.71,-0.00051,-0.0026,0.7,-1.5,-0.86,0.72,-13,-6.3,-3.7e+02,-0.0013,-0.0057,-0.00025,-0.024,-0.0017,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0085,0.31,0.29,0.036,3.4e-07,3.3e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -32290000,0.71,-0.00075,-0.0034,0.7,-1.5,-0.85,0.71,-14,-6.4,-3.7e+02,-0.0013,-0.0057,-0.00027,-0.025,-0.00014,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.2e-05,7.3e-05,2.4e-05,0.029,0.026,0.0086,0.32,0.31,0.036,3.4e-07,3.3e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -32390000,0.71,-0.00089,-0.004,0.7,-1.5,-0.84,0.71,-14,-6.5,-3.7e+02,-0.0013,-0.0057,-0.00028,-0.025,0.00072,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0085,0.32,0.3,0.037,3.3e-07,3.3e-07,1e-06,0.026,0.025,0.0005,0,0,0,0,0,0,0,0 -32490000,0.71,-0.001,-0.0042,0.7,-1.4,-0.82,0.72,-14,-6.6,-3.7e+02,-0.0013,-0.0057,-0.00029,-0.026,0.0018,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.03,0.026,0.0085,0.33,0.32,0.037,3.3e-07,3.3e-07,1e-06,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -32590000,0.71,-0.00094,-0.0044,0.7,-1.4,-0.81,0.72,-14,-6.7,-3.7e+02,-0.0013,-0.0057,-0.00031,-0.026,0.0026,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.028,0.025,0.0084,0.33,0.31,0.036,3.3e-07,3.2e-07,9.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -32690000,0.71,-0.00099,-0.0045,0.7,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-0.0013,-0.0057,-0.00032,-0.026,0.0032,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.1e-05,7.3e-05,2.4e-05,0.03,0.026,0.0085,0.34,0.32,0.036,3.3e-07,3.2e-07,9.8e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -32790000,0.71,-0.0009,-0.0045,0.7,-1.3,-0.79,0.71,-14,-6.8,-3.7e+02,-0.0013,-0.0057,-0.00034,-0.027,0.0041,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.1e-05,7.2e-05,2.3e-05,0.028,0.025,0.0084,0.34,0.32,0.036,3.2e-07,3.2e-07,9.7e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -32890000,0.71,-0.00081,-0.0044,0.7,-1.3,-0.78,0.71,-14,-6.9,-3.7e+02,-0.0013,-0.0057,-0.00036,-0.027,0.0051,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.1e-05,7.2e-05,2.3e-05,0.03,0.026,0.0084,0.35,0.33,0.036,3.2e-07,3.2e-07,9.6e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -32990000,0.71,-0.00061,-0.0044,0.7,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-0.0013,-0.0057,-0.00036,-0.028,0.0065,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.1e-05,7.2e-05,2.3e-05,0.028,0.025,0.0083,0.35,0.33,0.036,3.1e-07,3.2e-07,9.5e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33090000,0.71,-0.00065,-0.0044,0.7,-1.3,-0.76,0.7,-15,-7.1,-3.7e+02,-0.0013,-0.0057,-0.00036,-0.028,0.007,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.1e-05,7.2e-05,2.3e-05,0.03,0.026,0.0084,0.36,0.34,0.036,3.1e-07,3.2e-07,9.4e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33190000,0.71,0.0028,-0.0034,0.71,-1.2,-0.75,0.64,-15,-7.1,-3.7e+02,-0.0013,-0.0057,-0.00037,-0.028,0.0078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8e-05,7.2e-05,2.3e-05,0.028,0.025,0.0083,0.36,0.34,0.036,3.1e-07,3.1e-07,9.3e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33290000,0.66,0.015,-0.0025,0.76,-1.2,-0.73,0.62,-15,-7.2,-3.7e+02,-0.0013,-0.0057,-0.00037,-0.028,0.0082,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,7.9e-05,7.3e-05,2.5e-05,0.03,0.026,0.0083,0.37,0.35,0.036,3.1e-07,3.1e-07,9.2e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33390000,0.55,0.013,-0.0027,0.83,-1.2,-0.72,0.81,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00037,-0.029,0.0092,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00091,7.8e-05,7.3e-05,5.2e-05,0.028,0.025,0.0083,0.37,0.35,0.036,3e-07,3.1e-07,9.2e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33490000,0.41,0.0061,-0.00013,0.91,-1.2,-0.71,0.83,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00038,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00083,7.7e-05,7.5e-05,0.00012,0.03,0.026,0.0081,0.38,0.36,0.036,3e-07,3.1e-07,9.1e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33590000,0.26,0.00013,-0.0025,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00068,7.5e-05,7.6e-05,0.00023,0.029,0.026,0.0078,0.38,0.36,0.036,3e-07,3e-07,9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33690000,0.09,-0.0033,-0.0054,1,-1.1,-0.71,0.8,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00051,7.4e-05,7.8e-05,0.00035,0.032,0.029,0.0076,0.39,0.37,0.036,2.9e-07,3e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33790000,-0.081,-0.0048,-0.0071,1,-1.1,-0.69,0.78,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00032,7.1e-05,7.8e-05,0.00042,0.031,0.029,0.0074,0.38,0.36,0.036,2.9e-07,2.9e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33890000,-0.25,-0.0059,-0.0077,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7e-05,7.9e-05,0.00043,0.035,0.032,0.0072,0.39,0.38,0.036,2.8e-07,2.9e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -33990000,-0.39,-0.0041,-0.011,0.92,-0.96,-0.63,0.74,-16,-7.7,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,6.7e-05,7.6e-05,0.00039,0.034,0.032,0.007,0.38,0.37,0.035,2.8e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -34090000,-0.5,-0.003,-0.013,0.87,-0.9,-0.58,0.74,-16,-7.7,-3.7e+02,-0.0014,-0.0057,-0.00039,-0.029,0.0093,-0.091,0.37,0.0037,0.025,0,0,0,0,0,4.8e-05,6.7e-05,7.5e-05,0.00034,0.038,0.037,0.0069,0.39,0.38,0.036,2.8e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -34190000,-0.57,-0.0023,-0.011,0.82,-0.89,-0.54,0.74,-16,-7.8,-3.7e+02,-0.0014,-0.0057,-0.00038,-0.032,0.011,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,6.3e-05,7.1e-05,0.00028,0.038,0.037,0.0067,0.39,0.38,0.035,2.7e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -34290000,-0.61,-0.0032,-0.0086,0.79,-0.84,-0.49,0.74,-16,-7.9,-3.7e+02,-0.0014,-0.0057,-0.00038,-0.032,0.011,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,6.4e-05,7e-05,0.00024,0.043,0.043,0.0066,0.4,0.39,0.035,2.7e-07,2.8e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -34390000,-0.64,-0.0033,-0.0061,0.77,-0.83,-0.45,0.74,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00038,-0.037,0.016,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,5.9e-05,6.5e-05,0.00021,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-07,2.7e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -34490000,-0.65,-0.0042,-0.0039,0.76,-0.77,-0.41,0.73,-16,-8,-3.7e+02,-0.0015,-0.0057,-0.00038,-0.037,0.016,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.9e-05,6.5e-05,0.00018,0.049,0.05,0.0064,0.41,0.4,0.035,2.7e-07,2.7e-07,8.9e-07,0.026,0.024,0.0005,0,0,0,0,0,0,0,0 -34590000,-0.66,-0.0035,-0.0028,0.75,-0.78,-0.39,0.73,-17,-8,-3.7e+02,-0.0015,-0.0057,-0.00037,-0.047,0.025,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.4e-05,5.9e-05,0.00016,0.047,0.048,0.0063,0.4,0.4,0.034,2.7e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 -34690000,-0.67,-0.0039,-0.0021,0.74,-0.72,-0.35,0.73,-17,-8.1,-3.7e+02,-0.0015,-0.0057,-0.00037,-0.047,0.025,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,5.4e-05,5.9e-05,0.00015,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 -34790000,-0.67,-0.0027,-0.0018,0.74,-0.73,-0.34,0.72,-17,-8.2,-3.7e+02,-0.0015,-0.0057,-0.00036,-0.059,0.036,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,4.9e-05,5.3e-05,0.00013,0.051,0.052,0.0062,0.41,0.41,0.034,2.6e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 -34890000,-0.68,-0.0028,-0.0017,0.74,-0.68,-0.31,0.72,-17,-8.2,-3.7e+02,-0.0015,-0.0057,-0.00036,-0.059,0.036,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.9e-05,5.3e-05,0.00012,0.058,0.06,0.0062,0.42,0.42,0.034,2.7e-07,2.7e-07,8.9e-07,0.025,0.023,0.0005,0,0,0,0,0,0,0,0 -34990000,-0.68,-0.009,-0.0045,0.73,0.33,0.3,-0.13,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00036,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,0.00011,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-07,2.7e-07,8.9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35090000,-0.68,-0.009,-0.0046,0.73,0.45,0.33,-0.18,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,0.0001,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-07,2.7e-07,8.9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35190000,-0.68,-0.009,-0.0046,0.73,0.48,0.36,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,4.5e-05,4.9e-05,9.7e-05,0.067,0.068,0.0067,0.44,0.44,0.034,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35290000,-0.68,-0.0091,-0.0047,0.73,0.5,0.39,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,9.1e-05,0.072,0.074,0.0066,0.46,0.45,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35390000,-0.68,-0.0091,-0.0046,0.73,0.52,0.43,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00035,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,8.6e-05,0.078,0.08,0.0066,0.47,0.47,0.034,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35490000,-0.68,-0.0092,-0.0046,0.73,0.54,0.46,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00036,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,4.5e-05,4.9e-05,8.1e-05,0.084,0.086,0.0065,0.49,0.49,0.034,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35590000,-0.68,-0.006,-0.0046,0.73,0.43,0.37,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00033,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.8e-05,4.1e-05,7.6e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35690000,-0.68,-0.006,-0.0046,0.73,0.45,0.4,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00033,-0.073,0.051,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.8e-05,4.1e-05,7.3e-05,0.072,0.074,0.0061,0.49,0.49,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35790000,-0.68,-0.0037,-0.0045,0.73,0.37,0.34,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00031,-0.075,0.052,-0.091,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,3.3e-05,3.5e-05,6.9e-05,0.06,0.062,0.0059,0.49,0.48,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35890000,-0.68,-0.0037,-0.0046,0.73,0.39,0.37,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00031,-0.075,0.052,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,3.3e-05,3.5e-05,6.6e-05,0.066,0.067,0.0058,0.5,0.5,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -35990000,-0.68,-0.0018,-0.0045,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.0003,-0.082,0.059,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,2.9e-05,3.1e-05,6.3e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-07,2.7e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -36090000,-0.68,-0.0019,-0.0045,0.73,0.34,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.0003,-0.082,0.059,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3e-05,2.9e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-07,2.8e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -36190000,-0.68,-0.00038,-0.0044,0.73,0.28,0.28,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00029,-0.093,0.068,-0.091,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.6e-05,2.7e-05,5.8e-05,0.054,0.056,0.0055,0.5,0.5,0.032,2.7e-07,2.8e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -36290000,-0.68,-0.00049,-0.0043,0.73,0.29,0.3,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00029,-0.093,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.6e-05,2.7e-05,5.6e-05,0.06,0.061,0.0056,0.52,0.52,0.032,2.7e-07,2.8e-07,9e-07,0.024,0.022,0.0005,0,0,0,0,0,0,0,0 -36390000,-0.68,0.00062,-0.0043,0.73,0.24,0.26,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00028,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.1e-05,2.3e-05,2.5e-05,5.4e-05,0.053,0.054,0.0055,0.51,0.51,0.032,2.8e-07,2.8e-07,9.1e-07,0.023,0.021,0.0005,0,0,0,0,0,0,0,0 -36490000,-0.68,0.00054,-0.0043,0.73,0.25,0.27,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00027,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.3e-05,2.5e-05,5.2e-05,0.058,0.06,0.0055,0.52,0.52,0.032,2.8e-07,2.8e-07,9.1e-07,0.023,0.021,0.0005,0,0,0,0,0,0,0,0 -36590000,-0.68,0.0014,-0.0042,0.73,0.21,0.24,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00027,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.1e-05,2.3e-05,5e-05,0.052,0.053,0.0055,0.52,0.52,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.021,0.0005,0,0,0,0,0,0,0,0 -36690000,-0.68,0.0014,-0.0042,0.73,0.21,0.25,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00027,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.2e-05,2.2e-05,2.3e-05,4.9e-05,0.058,0.059,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.021,0.0005,0,0,0,0,0,0,0,0 -36790000,-0.68,0.002,-0.0041,0.73,0.18,0.22,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00026,-0.13,0.098,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,2e-05,2.1e-05,4.7e-05,0.051,0.053,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.02,0.0005,0,0,0,0,0,0,0,0 -36890000,-0.68,0.0019,-0.0041,0.73,0.18,0.23,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00026,-0.13,0.098,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,2e-05,2.1e-05,4.6e-05,0.057,0.058,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,9.1e-07,0.022,0.02,0.0005,0,0,0,0,0,0,0,0 -36990000,-0.68,0.0024,-0.0039,0.73,0.15,0.2,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00026,-0.14,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,1.9e-05,2e-05,4.4e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,9.1e-07,0.021,0.02,0.0005,0,0,0,0,0,0,0,0 -37090000,-0.68,0.0023,-0.0039,0.73,0.15,0.21,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00025,-0.14,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.9e-05,2e-05,4.3e-05,0.056,0.057,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,9.1e-07,0.021,0.02,0.0005,0,0,0,0,0,0,0,0 -37190000,-0.68,0.0027,-0.0038,0.73,0.12,0.18,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00025,-0.16,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.8e-05,1.9e-05,4.2e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-07,2.9e-07,9.1e-07,0.02,0.019,0.0005,0,0,0,0,0,0,0,0 -37290000,-0.68,0.0027,-0.0039,0.74,0.12,0.18,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00024,-0.16,0.12,-0.093,0.37,0.0037,0.025,0,0,0,0,0,3.4e-05,1.8e-05,1.9e-05,4.1e-05,0.055,0.056,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,9.1e-07,0.02,0.019,0.0005,0,0,0,0,0,0,0,0 -37390000,-0.68,0.0029,-0.0037,0.74,0.099,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00024,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.8e-05,1.9e-05,4e-05,0.049,0.05,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,9.1e-07,0.019,0.018,0.0005,0,0,0,0,0,0,0,0 -37490000,-0.68,0.0029,-0.0037,0.74,0.098,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00023,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.8e-05,1.9e-05,3.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-07,2.9e-07,9.1e-07,0.019,0.018,0.0005,0,0,0,0,0,0,0,0 -37590000,-0.68,0.003,-0.0036,0.74,0.078,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00023,-0.18,0.13,-0.094,0.37,0.0037,0.025,0,0,0,0,0,3.5e-05,1.7e-05,1.8e-05,3.8e-05,0.048,0.049,0.0061,0.57,0.57,0.031,2.9e-07,2.9e-07,9.1e-07,0.018,0.017,0.0005,0,0,0,0,0,0,0,0 -37690000,-0.68,0.003,-0.0036,0.74,0.075,0.14,-0.11,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00023,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,1.7e-05,1.8e-05,3.7e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-07,2.9e-07,9.1e-07,0.018,0.017,0.0005,0,0,0,0,0,0,0,0 -37790000,-0.68,0.0031,-0.0036,0.74,0.058,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00022,-0.19,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,1.7e-05,1.8e-05,3.6e-05,0.047,0.048,0.0063,0.58,0.58,0.03,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 -37890000,-0.68,0.0031,-0.0036,0.74,0.055,0.13,-0.095,-17,-8.2,-3.7e+02,-0.0017,-0.0058,-0.00022,-0.19,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.5e-05,0.051,0.052,0.0064,0.59,0.59,0.03,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 -37990000,-0.68,0.0032,-0.0036,0.74,0.04,0.11,-0.086,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00021,-0.19,0.14,-0.096,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.4e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 -38090000,-0.68,0.0031,-0.0036,0.74,0.035,0.11,-0.076,-17,-8.2,-3.7e+02,-0.0017,-0.0057,-0.00021,-0.19,0.14,-0.096,0.37,0.0037,0.025,0,0,0,0,0,3.7e-05,1.7e-05,1.8e-05,3.4e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-07,2.9e-07,9.2e-07,0.017,0.016,0.0005,0,0,0,0,0,0,0,0 -38190000,-0.68,0.0032,-0.0036,0.74,0.022,0.096,-0.068,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.0002,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-07,2.9e-07,9.2e-07,0.016,0.015,0.0005,0,0,0,0,0,0,0,0 -38290000,-0.68,0.0032,-0.0036,0.74,0.018,0.098,-0.061,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.0002,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.2e-05,0.049,0.049,0.0068,0.61,0.61,0.031,2.9e-07,3e-07,9.2e-07,0.016,0.015,0.0005,0,0,0,0,0,0,0,0 -38390000,-0.68,0.0032,-0.0035,0.74,0.0092,0.084,-0.053,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00019,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,1.7e-05,1.8e-05,3.2e-05,0.044,0.044,0.0069,0.61,0.61,0.031,2.9e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 -38490000,-0.68,0.0032,-0.0035,0.74,0.005,0.087,-0.046,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00019,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3.1e-05,0.047,0.048,0.007,0.62,0.62,0.031,3e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 -38590000,-0.68,0.0032,-0.0034,0.74,0.00025,0.074,-0.039,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00018,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3e-05,0.043,0.043,0.0071,0.62,0.62,0.031,3e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 -38690000,-0.68,0.0031,-0.0034,0.74,-0.005,0.074,-0.032,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00018,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,1.7e-05,1.8e-05,3e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-07,3e-07,9.2e-07,0.015,0.014,0.0005,0,0,0,0,0,0,0,0 -38790000,-0.68,0.0031,-0.0034,0.74,-0.01,0.062,-0.024,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00017,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,4e-05,1.7e-05,1.8e-05,2.9e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-07,3e-07,9.2e-07,0.014,0.013,0.0005,0,0,0,0,0,0,0,0 -38890000,-0.68,0.0029,-0.0034,0.74,-0.021,0.052,0.48,-17,-8.2,-3.7e+02,-0.0016,-0.0057,-0.00017,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,4e-05,1.7e-05,1.8e-05,2.9e-05,0.044,0.045,0.0075,0.64,0.64,0.032,3e-07,3e-07,9.2e-07,0.014,0.013,0.0005,0,0,0,0,0,0,0,0 +10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.1e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,4.9e-07,0.0025,0.0025,0.00025,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.2e-07,0.0026,0.0026,0.00032,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +190000,1,-0.0094,-0.011,2.9e-05,6.9e-05,0.0039,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-2e-09,0,0,0,0,0,0,0,0,5.6e-07,0.0027,0.0027,0.00044,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +290000,1,-0.0094,-0.011,6.4e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.8e-11,0,0,-4.8e-07,0,0,0,0,0,0,0,0,6.2e-07,0.0029,0.0029,0.00021,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +390000,1,-0.0095,-0.011,7.2e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.6e-10,0,0,-4.5e-06,0,0,0,0,0,0,0,0,6.8e-07,0.0031,0.0031,0.0003,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +490000,1,-0.0095,-0.012,2.2e-05,0.0039,0.0048,-0.06,0.00024,0.00048,-0.011,1.6e-06,-3.7e-07,-3.5e-08,0,0,-1.6e-05,0,0,0,0,0,0,0,0,7.7e-07,0.0034,0.0034,0.00018,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +590000,1,-0.0095,-0.012,2.9e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-3.4e-08,0,0,-3.4e-05,0,0,0,0,0,0,0,0,8.7e-07,0.0037,0.0037,0.00026,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +690000,1,-0.0097,-0.012,8.9e-05,0.0063,0.0051,-0.06,0.0005,0.00054,-0.013,5.5e-06,-3.2e-06,-1.2e-07,0,0,-6.3e-05,0,0,0,0,0,0,0,0,9.9e-07,0.004,0.004,0.00016,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0025,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +790000,1,-0.0098,-0.013,0.0001,0.0086,0.0072,-0.063,0.0012,0.0011,-0.014,5.4e-06,-3.1e-06,-1.2e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.1e-06,0.0044,0.0044,0.00022,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0025,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +890000,1,-0.0099,-0.013,0.00012,0.01,0.0059,-0.077,0.00096,0.00071,-0.021,1.6e-05,-1.5e-05,-3.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.3e-06,0.0048,0.0048,0.00014,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.0016,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +990000,1,-0.0099,-0.013,0.00013,0.015,0.0062,-0.092,0.0022,0.0013,-0.029,1.6e-05,-1.5e-05,-3.6e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.5e-06,0.0053,0.0053,0.00018,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.0016,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1090000,1,-0.01,-0.014,0.00013,0.016,0.0048,-0.11,0.0018,0.00084,-0.039,4.1e-05,-6.2e-05,-9e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.6e-06,0.0057,0.0057,0.00013,0.92,0.92,2,0.17,0.17,0.84,0.0098,0.0098,0.001,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1190000,1,-0.01,-0.014,0.00011,0.02,0.005,-0.12,0.0035,0.0013,-0.051,4.1e-05,-6.2e-05,-9e-07,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.8e-06,0.0063,0.0063,0.00016,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.001,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1290000,1,-0.01,-0.014,0.00016,0.02,0.0041,-0.14,0.0027,0.00085,-0.064,8.2e-05,-0.00019,-1.7e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,1.9e-06,0.0064,0.0064,0.00011,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1390000,1,-0.01,-0.014,0.00017,0.026,0.0038,-0.15,0.0051,0.0013,-0.078,8.2e-05,-0.00019,-1.7e-06,0,0,-9.6e-05,0,0,0,0,0,0,0,0,2.2e-06,0.0071,0.0071,0.00014,1.1,1.1,2,0.21,0.21,1.7,0.0095,0.0095,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1490000,1,-0.01,-0.014,0.00015,0.024,0.0026,-0.16,0.0038,0.00078,-0.093,0.00014,-0.00046,-2.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,2.2e-06,0.0067,0.0067,0.0001,0.95,0.95,2,0.14,0.14,2.1,0.0088,0.0088,0.00047,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1590000,1,-0.011,-0.014,0.00014,0.031,0.003,-0.18,0.0065,0.0011,-0.11,0.00014,-0.00046,-2.7e-06,0,0,-9.8e-05,0,0,0,0,0,0,0,0,2.4e-06,0.0074,0.0074,0.00012,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00047,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1690000,1,-0.011,-0.014,0.00011,0.028,-0.00047,-0.19,0.0045,0.00057,-0.13,0.00019,-0.00088,-3.2e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,2.2e-06,0.0064,0.0064,9.1e-05,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00034,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1790000,1,-0.011,-0.014,7.9e-05,0.035,-0.0024,-0.2,0.0076,0.00044,-0.15,0.00019,-0.00088,-3.2e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,2.4e-06,0.007,0.007,0.00011,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00034,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1890000,1,-0.011,-0.015,5.9e-05,0.043,-0.0037,-0.22,0.011,0.00014,-0.17,0.00019,-0.00088,-3.2e-06,0,0,-0.0001,0,0,0,0,0,0,0,0,2.7e-06,0.0076,0.0076,0.00012,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00034,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1990000,1,-0.011,-0.014,5.4e-05,0.036,-0.0051,-0.23,0.0082,-0.00038,-0.19,0.0002,-0.0014,-2.1e-06,0,0,-0.00011,0,0,0,0,0,0,0,0,2.2e-06,0.0061,0.0061,9.6e-05,1.3,1.3,2,0.2,0.2,4.7,0.0066,0.0066,0.00026,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2090000,1,-0.011,-0.014,1.4e-05,0.041,-0.0077,-0.24,0.012,-0.001,-0.22,0.0002,-0.0014,-2.1e-06,0,0,-0.00011,0,0,0,0,0,0,0,0,2.4e-06,0.0066,0.0066,0.00011,1.7,1.7,2.1,0.31,0.31,5.3,0.0066,0.0066,0.00026,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2190000,1,-0.011,-0.014,8e-06,0.033,-0.0072,-0.26,0.0079,-0.0011,-0.24,0.00015,-0.002,3e-07,0,0,-0.00011,0,0,0,0,0,0,0,0,1.8e-06,0.005,0.005,8.7e-05,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2290000,1,-0.011,-0.014,-7.2e-06,0.039,-0.0098,-0.27,0.011,-0.0019,-0.27,0.00015,-0.002,3e-07,0,0,-0.00011,0,0,0,0,0,0,0,0,2e-06,0.0054,0.0054,9.8e-05,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,0.0002,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2390000,1,-0.011,-0.013,-7.3e-06,0.03,-0.009,-0.29,0.0074,-0.0016,-0.3,5.8e-05,-0.0025,3.5e-06,0,0,-0.00011,0,0,0,0,0,0,0,0,1.5e-06,0.004,0.004,7.9e-05,1,1,2.1,0.19,0.19,7.4,0.0045,0.0045,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2490000,1,-0.011,-0.013,-2.7e-05,0.034,-0.011,-0.3,0.011,-0.0025,-0.32,5.8e-05,-0.0025,3.5e-06,0,0,-0.00011,0,0,0,0,0,0,0,0,1.6e-06,0.0044,0.0044,8.9e-05,1.3,1.3,2.1,0.28,0.28,8.2,0.0045,0.0045,0.00015,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2590000,1,-0.011,-0.013,-2.9e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-5.2e-05,-0.003,7.1e-06,0,0,-0.00011,0,0,0,0,0,0,0,0,1.2e-06,0.0032,0.0032,7.3e-05,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,0.00012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2690000,1,-0.011,-0.013,-3.5e-05,0.03,-0.011,-0.33,0.0096,-0.0029,-0.39,-5.2e-05,-0.003,7.1e-06,0,0,-0.00011,0,0,0,0,0,0,0,0,1.3e-06,0.0035,0.0035,8.1e-05,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,0.00012,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2790000,1,-0.011,-0.013,-5.5e-05,0.023,-0.0096,-0.34,0.0061,-0.002,-0.42,-0.00017,-0.0033,1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1e-06,0.0027,0.0027,6.7e-05,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,9.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2890000,1,-0.011,-0.013,-0.00011,0.027,-0.011,-0.35,0.0086,-0.003,-0.46,-0.00017,-0.0033,1e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,1.1e-06,0.0029,0.0029,7.4e-05,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,9.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +2990000,1,-0.011,-0.013,-7.3e-05,0.022,-0.0097,-0.36,0.0056,-0.0021,-0.49,-0.00028,-0.0036,1.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,8.4e-07,0.0023,0.0023,6.2e-05,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3090000,1,-0.011,-0.013,-7.4e-05,0.024,-0.011,-0.38,0.0079,-0.0032,-0.53,-0.00028,-0.0036,1.4e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,9.3e-07,0.0025,0.0025,6.9e-05,0.82,0.82,2.2,0.22,0.22,14,0.0027,0.0027,8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3190000,1,-0.011,-0.013,-0.00014,0.019,-0.0088,-0.39,0.0052,-0.0022,-0.57,-0.00039,-0.0039,1.7e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,7.2e-07,0.002,0.002,5.8e-05,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,6.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3290000,1,-0.011,-0.013,-0.00011,0.023,-0.011,-0.4,0.0073,-0.0031,-0.61,-0.00039,-0.0039,1.7e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,7.9e-07,0.0022,0.0022,6.4e-05,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,6.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3390000,1,-0.011,-0.012,-0.00015,0.018,-0.0094,-0.42,0.0049,-0.0022,-0.65,-0.00049,-0.0041,1.9e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,6.2e-07,0.0017,0.0017,5.5e-05,0.53,0.53,2.3,0.14,0.14,17,0.0019,0.0019,5.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3490000,1,-0.011,-0.013,-0.00016,0.021,-0.012,-0.43,0.0068,-0.0032,-0.69,-0.00049,-0.0041,1.9e-05,0,0,-0.00011,0,0,0,0,0,0,0,0,6.8e-07,0.0019,0.0019,6e-05,0.65,0.65,2.3,0.19,0.19,19,0.0019,0.0019,5.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3590000,1,-0.011,-0.012,-0.00014,0.017,-0.011,-0.44,0.0046,-0.0023,-0.73,-0.0006,-0.0044,2.2e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.4e-07,0.0015,0.0015,5.2e-05,0.48,0.48,2.4,0.13,0.13,20,0.0016,0.0016,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3690000,1,-0.011,-0.012,-2.6e-05,0.019,-0.014,-0.46,0.0064,-0.0036,-0.78,-0.0006,-0.0044,2.2e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.9e-07,0.0017,0.0017,5.6e-05,0.59,0.59,2.4,0.18,0.18,21,0.0016,0.0016,4.7e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3790000,1,-0.011,-0.012,8.9e-06,0.015,-0.014,-0.47,0.0043,-0.0026,-0.83,-0.00072,-0.0045,2.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,4.7e-07,0.0014,0.0014,4.9e-05,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3890000,1,-0.011,-0.012,-2.9e-05,0.017,-0.015,-0.48,0.006,-0.004,-0.87,-0.00072,-0.0045,2.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.1e-07,0.0015,0.0015,5.3e-05,0.54,0.54,2.4,0.17,0.17,24,0.0014,0.0014,4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +3990000,1,-0.011,-0.012,-2.9e-05,0.02,-0.016,-0.5,0.0078,-0.0056,-0.92,-0.00072,-0.0045,2.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,5.5e-07,0.0016,0.0016,5.7e-05,0.66,0.66,2.5,0.23,0.23,26,0.0014,0.0014,4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4090000,1,-0.011,-0.012,-4.4e-05,0.017,-0.014,-0.51,0.0056,-0.0042,-0.97,-0.00084,-0.0047,2.8e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,4.3e-07,0.0013,0.0013,5e-05,0.5,0.5,2.5,0.16,0.16,27,0.0012,0.0012,3.5e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4190000,1,-0.011,-0.012,-7.2e-05,0.02,-0.017,-0.53,0.0075,-0.0057,-1,-0.00084,-0.0047,2.8e-05,0,0,-9.6e-05,0,0,0,0,0,0,0,0,4.7e-07,0.0015,0.0015,5.3e-05,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,3.5e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4290000,1,-0.01,-0.012,-0.00013,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00097,-0.0049,3.1e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,3.7e-07,0.0012,0.0012,4.7e-05,0.46,0.46,2.6,0.15,0.15,31,0.00095,0.00096,3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4390000,1,-0.01,-0.012,-0.00011,0.018,-0.013,-0.55,0.0072,-0.0055,-1.1,-0.00097,-0.0049,3.1e-05,0,0,-9.1e-05,0,0,0,0,0,0,0,0,4e-07,0.0013,0.0013,5e-05,0.56,0.56,2.6,0.2,0.2,33,0.00095,0.00096,3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4490000,1,-0.01,-0.012,-6.1e-05,0.015,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,3.4e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,3.2e-07,0.001,0.001,4.5e-05,0.43,0.43,2.6,0.14,0.14,34,0.00078,0.00079,2.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4590000,1,-0.01,-0.012,-3.6e-05,0.018,-0.012,-0.58,0.0068,-0.0049,-1.2,-0.0011,-0.005,3.4e-05,0,0,-8.7e-05,0,0,0,0,0,0,0,0,3.4e-07,0.0011,0.0011,4.8e-05,0.51,0.51,2.7,0.19,0.19,36,0.00078,0.00079,2.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4690000,1,-0.01,-0.012,-4.3e-05,0.014,-0.01,-0.6,0.0049,-0.0034,-1.3,-0.0012,-0.0052,3.7e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,2.7e-07,0.00091,0.00092,4.3e-05,0.39,0.39,2.7,0.14,0.14,38,0.00064,0.00064,2.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4790000,1,-0.01,-0.012,-5.7e-05,0.016,-0.012,-0.61,0.0064,-0.0045,-1.4,-0.0012,-0.0052,3.7e-05,0,0,-8.2e-05,0,0,0,0,0,0,0,0,2.9e-07,0.00099,0.00099,4.5e-05,0.47,0.47,2.7,0.18,0.18,40,0.00064,0.00064,2.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4890000,1,-0.01,-0.012,-8e-05,0.013,-0.01,-0.63,0.0046,-0.0033,-1.4,-0.0013,-0.0053,3.9e-05,0,0,-7.8e-05,0,0,0,0,0,0,0,0,2.3e-07,0.0008,0.0008,4.1e-05,0.36,0.36,2.8,0.13,0.13,42,0.00052,0.00052,2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +4990000,1,-0.01,-0.012,-0.00011,0.015,-0.011,-0.64,0.006,-0.0043,-1.5,-0.0013,-0.0053,3.9e-05,0,0,-7.8e-05,0,0,0,0,0,0,0,0,2.4e-07,0.00086,0.00086,4.3e-05,0.43,0.43,2.8,0.17,0.17,44,0.00052,0.00052,2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5090000,1,-0.01,-0.011,-6.9e-05,0.012,-0.0086,-0.66,0.0043,-0.0031,-1.6,-0.0013,-0.0054,4e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,1.9e-07,0.00069,0.00069,3.9e-05,0.33,0.33,2.8,0.12,0.12,46,0.00042,0.00042,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5190000,1,-0.01,-0.011,-4.7e-05,0.013,-0.01,-0.67,0.0056,-0.004,-1.6,-0.0013,-0.0054,4e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,2e-07,0.00075,0.00075,4.1e-05,0.39,0.39,2.9,0.16,0.16,49,0.00042,0.00042,1.8e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5290000,1,-0.01,-0.011,-6.6e-05,0.0093,-0.0074,-0.68,0.0039,-0.0029,-1.7,-0.0014,-0.0055,4.2e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,1.6e-07,0.0006,0.0006,3.7e-05,0.3,0.3,2.9,0.12,0.12,51,0.00034,0.00034,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5390000,1,-0.0099,-0.011,-1.3e-05,0.0088,-0.0083,-0.7,0.0048,-0.0037,-1.8,-0.0014,-0.0055,4.2e-05,0,0,-6.9e-05,0,0,0,0,0,0,0,0,1.7e-07,0.00064,0.00064,3.9e-05,0.36,0.36,2.9,0.16,0.16,53,0.00034,0.00034,1.6e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5490000,1,-0.0098,-0.011,-9.4e-06,0.0061,-0.0064,-0.71,0.0032,-0.0026,-1.8,-0.0014,-0.0055,4.3e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,1.3e-07,0.00052,0.00052,3.6e-05,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5590000,1,-0.0098,-0.011,-3.5e-05,0.0069,-0.0068,-0.73,0.0039,-0.0032,-1.9,-0.0014,-0.0055,4.3e-05,0,0,-6.6e-05,0,0,0,0,0,0,0,0,1.4e-07,0.00055,0.00055,3.8e-05,0.33,0.33,3,0.15,0.15,58,0.00028,0.00028,1.4e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5690000,1,-0.0096,-0.011,3.1e-05,0.0048,-0.004,-0.74,0.0027,-0.0022,-2,-0.0015,-0.0056,4.4e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,1.1e-07,0.00045,0.00045,3.4e-05,0.25,0.25,3.1,0.11,0.11,61,0.00022,0.00022,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5790000,1,-0.0096,-0.011,2.3e-05,0.0052,-0.003,-0.75,0.0031,-0.0026,-2,-0.0015,-0.0056,4.4e-05,0,0,-6.3e-05,0,0,0,0,0,0,0,0,1.2e-07,0.00048,0.00048,3.6e-05,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,1.3e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5890000,1,-0.0095,-0.011,-6.7e-06,0.0045,-0.0011,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,9e-08,0.00038,0.00038,3.3e-05,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +5990000,1,-0.0094,-0.011,1.1e-05,0.0048,0.00032,0.015,0.0026,-0.0017,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,9.6e-08,0.00041,0.00041,3.5e-05,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6090000,1,-0.0094,-0.011,-7.9e-06,0.0059,0.0015,-0.011,0.0031,-0.0016,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,1e-07,0.00044,0.00044,3.7e-05,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6190000,0.7,0.0013,-0.015,0.71,0.0035,0.0029,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00076,0.00034,0.00034,0.00076,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6290000,0.71,0.0013,-0.015,0.71,0.0034,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0005,0.00034,0.00034,0.00049,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6390000,0.71,0.0013,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-3.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00039,0.00034,0.00034,0.00038,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6490000,0.71,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-8.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00032,0.00034,0.00034,0.0003,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6590000,0.71,0.0014,-0.014,0.71,0.0016,0.0057,-0.099,0.0033,0.0013,-3.7e+02,-0.0015,-0.0057,4.4e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00027,0.00034,0.00034,0.00024,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6690000,0.7,0.0014,-0.014,0.71,0.002,0.0068,-0.076,0.0035,0.0019,-3.7e+02,-0.0015,-0.0057,4.2e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.00023,0.00035,0.00035,0.00021,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6790000,0.71,0.0014,-0.014,0.71,0.00075,0.0067,-0.11,0.0036,0.0026,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,8.1e-06,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.00035,0.00035,0.00018,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6890000,0.71,0.0014,-0.014,0.71,-0.0013,0.0073,-0.12,0.0036,0.0033,-3.7e+02,-0.0015,-0.0057,4.4e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00036,0.00036,0.00016,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00015,1.1e-05,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,3.8e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00036,0.00036,0.00015,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7090000,0.7,0.0015,-0.014,0.71,-0.0018,0.0078,-0.13,0.0033,0.0048,-3.7e+02,-0.0015,-0.0057,3.3e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00037,0.00037,0.00013,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7190000,0.7,0.0015,-0.014,0.71,-0.0035,0.008,-0.15,0.003,0.0056,-3.7e+02,-0.0015,-0.0057,3e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.00015,0.00038,0.00038,0.00012,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,1.1e-05,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.0082,-0.15,0.0026,0.0064,-3.7e+02,-0.0015,-0.0057,2.9e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.00039,0.00039,0.00011,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7390000,0.7,0.0015,-0.014,0.71,-0.0051,0.0097,-0.16,0.0021,0.0072,-3.7e+02,-0.0015,-0.0057,2.9e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00039,0.00039,0.00011,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7490000,0.7,0.0016,-0.014,0.71,-0.0067,0.01,-0.16,0.0015,0.0082,-3.7e+02,-0.0015,-0.0057,2.8e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.0004,0.0004,9.8e-05,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,1e-05,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.011,-0.17,0.0007,0.0092,-3.7e+02,-0.0015,-0.0057,3.2e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00041,0.00041,9.2e-05,0.52,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,1e-05,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,3.1e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00042,0.00042,8.7e-05,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,1e-05,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,2.2e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00043,0.00043,8.2e-05,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,1e-05,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.0027,0.013,-3.7e+02,-0.0015,-0.0057,2.4e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00045,0.00045,7.8e-05,0.66,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,1e-05,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.0042,0.014,-3.7e+02,-0.0015,-0.0057,2.6e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.00046,0.00046,7.4e-05,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,1e-05,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,3.2e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.00047,0.00047,7.1e-05,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,1e-05,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,2.5e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,9.7e-05,0.00049,0.00049,6.8e-05,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,1e-05,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.0057,2e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,9.4e-05,0.0005,0.0005,6.5e-05,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +8390000,0.7,0.0019,-0.014,0.71,-0.024,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0057,2.5e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,9.2e-05,0.00051,0.00051,6.3e-05,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,1e-05,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,2.1e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,9e-05,0.00052,0.00052,6e-05,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,1e-05,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,1.3e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,8.8e-05,0.00054,0.00054,5.8e-05,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,1e-05,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.025,-3.7e+02,-0.0015,-0.0056,2.2e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,8.6e-05,0.00055,0.00055,5.7e-05,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,1e-05,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,1.6e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,0.00056,0.00056,5.5e-05,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,1e-05,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.027,-0.15,-0.027,0.029,-3.7e+02,-0.0015,-0.0056,1.1e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,8.3e-05,0.00057,0.00057,5.3e-05,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,1e-05,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.031,-3.7e+02,-0.0015,-0.0056,2.6e-06,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,8.2e-05,0.00059,0.00059,5.2e-05,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,1e-05,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,-3.9e-06,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,8e-05,0.0006,0.0006,5e-05,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,1e-05,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.035,-3.7e+02,-0.0015,-0.0056,1.2e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,7.9e-05,0.00062,0.00062,4.9e-05,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.027,0,0,0,0,0,0,0,0 +9290000,0.7,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.041,0.036,-3.7e+02,-0.0015,-0.0056,1.3e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,7.8e-05,0.00062,0.00062,4.8e-05,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,1e-05,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.032,-0.14,-0.045,0.039,-3.7e+02,-0.0015,-0.0056,1.2e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00064,0.00064,4.7e-05,1.7,1.7,0.093,5.9,5.9,0.086,0.00013,0.00013,1e-05,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,2.4e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,7.6e-05,0.00064,0.00064,4.6e-05,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,1e-05,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,2.7e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,0.00066,0.00066,4.5e-05,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +9690000,0.7,0.0021,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,1.1e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.00065,0.00065,4.4e-05,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +9790000,0.7,0.0021,-0.014,0.71,-0.048,0.037,-0.11,-0.059,0.046,-3.7e+02,-0.0015,-0.0056,2e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00067,0.00067,4.3e-05,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +9890000,0.7,0.002,-0.014,0.71,-0.048,0.037,-0.11,-0.059,0.046,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00067,0.00067,4.2e-05,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.018,0,0,0,0,0,0,0,0 +9990000,0.7,0.0021,-0.014,0.71,-0.05,0.038,-0.1,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,9.1e-06,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,0.00069,0.00069,4.2e-05,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,1e-05,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.064,0.049,-3.7e+02,-0.0015,-0.0056,1.1e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,0.00068,0.00068,4.1e-05,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +10190000,0.7,0.0021,-0.014,0.71,-0.05,0.04,-0.096,-0.069,0.052,-3.7e+02,-0.0015,-0.0056,-1.1e-05,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.0007,0.0007,4e-05,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10290000,0.7,0.0021,-0.014,0.71,-0.052,0.04,-0.084,-0.075,0.056,-3.7e+02,-0.0015,-0.0056,-2.6e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00072,0.00072,4e-05,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,1e-05,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,-2.7e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00075,0.00075,3.9e-05,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,9.9e-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.0083,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,-4.2e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00077,0.00077,3.9e-05,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,9.9e-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.4e-05,-0.00027,3e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00078,0.00078,3.8e-05,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,9.8e-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.0058,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,-5e-05,-0.00027,3.2e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.0008,0.0008,3.8e-05,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,9.8e-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.0031,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,-5.1e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00077,0.00077,3.8e-05,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,9.7e-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.004,-0.0017,0.02,0.0031,-0.00093,-3.7e+02,-0.0014,-0.0056,-5.4e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.0008,0.0008,3.7e-05,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,9.7e-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.0068,0.0033,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,-4.4e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00073,0.00073,3.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,9.6e-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.0056,0.0058,0.019,0.0054,-0.0018,-3.7e+02,-0.0014,-0.0055,-3.2e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00075,0.00075,3.7e-05,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,9.6e-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.011,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,-4.7e-05,-0.00092,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00065,0.00065,3.6e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,9.5e-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,-6.9e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00067,0.00067,3.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,9.5e-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.0054,0.0091,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,-8.5e-05,-0.00051,0.00087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00055,0.00055,3.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,9.4e-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.0029,0.012,0.0025,0.006,-0.0009,-3.7e+02,-0.0013,-0.0056,-0.00012,-0.00051,0.00087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00057,0.00057,3.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,9.4e-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.0015,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,-0.00013,-9.1e-05,0.00074,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00047,0.00047,3.5e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11690000,0.7,0.0021,-0.014,0.71,-0.0043,0.013,-0.0079,0.0042,-0.00027,-3.7e+02,-0.0014,-0.0056,-0.00014,-8.2e-05,0.00073,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00048,0.00048,3.5e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11790000,0.7,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,-0.00014,2.4e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0004,0.0004,3.5e-05,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.4e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11890000,0.7,0.0021,-0.014,0.71,-0.011,0.014,-0.011,0.00079,0.0019,-3.7e+02,-0.0014,-0.0056,-0.00016,1.8e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00041,0.00041,3.5e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.4e-05,9.1e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11990000,0.7,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.00028,0.0023,-3.7e+02,-0.0014,-0.0057,-0.00016,0.00016,0.00055,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00034,0.00034,3.5e-05,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,9.1e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12090000,0.7,0.0021,-0.014,0.71,-0.014,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,-0.00015,0.00018,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00035,0.00035,3.5e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12190000,0.7,0.0018,-0.014,0.71,-0.0079,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,-0.00014,0.00043,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0003,0.0003,3.4e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,8.9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12290000,0.7,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00056,0.0033,-3.7e+02,-0.0013,-0.0057,-0.00014,0.0004,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00031,0.00031,3.4e-05,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,8.9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12390000,0.7,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,-0.00015,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00027,0.00027,3.4e-05,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,8.8e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12490000,0.7,0.0014,-0.014,0.71,-0.0062,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,-0.00017,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00028,0.00028,3.4e-05,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,8.7e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12590000,0.7,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,-0.00017,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00025,0.00025,3.4e-05,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,8.7e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 +12690000,0.7,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,-0.00018,0.00071,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00026,0.00026,3.4e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,8.6e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0 +12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0058,-0.00018,0.00075,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00023,0.00023,3.4e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,8.5e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 +12890000,0.7,0.0015,-0.013,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0058,-0.00017,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00024,0.00024,3.4e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,8.5e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0 +12990000,0.7,0.0012,-0.014,0.71,-0.0083,0.0065,-0.03,-0.001,0.0012,-3.7e+02,-0.0013,-0.0059,-0.00015,0.00067,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00022,0.00022,3.4e-05,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,8.4e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 +13090000,0.7,0.0012,-0.014,0.71,-0.009,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0013,-0.0059,-0.00018,0.00063,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00023,0.00023,3.4e-05,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,8.3e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 +13190000,0.7,0.00095,-0.014,0.71,5.5e-05,0.0061,-0.027,0.0044,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00018,0.00049,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13290000,0.7,0.00096,-0.014,0.71,-0.0002,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,-0.00016,0.00036,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00022,0.00022,3.4e-05,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,8.2e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13390000,0.7,0.00081,-0.014,0.71,0.00061,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00019,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00021,0.00021,3.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,8.1e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 +13490000,0.7,0.00084,-0.014,0.71,0.00012,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,-0.00013,0.00011,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00021,0.00021,3.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,8e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 +13590000,0.7,0.00078,-0.014,0.71,0.00037,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.0059,-0.00014,8.1e-05,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0002,0.0002,3.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,8e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 +13690000,0.7,0.00075,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.0059,-0.00011,0.00011,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,7.9e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 +13790000,0.7,0.00064,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,-0.00011,-0.00011,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0002,0.0002,3.4e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,7.8e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 +13890000,0.7,0.00061,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,-0.0001,-7.3e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,7.7e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 +13990000,0.7,0.00054,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,-9.6e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0002,0.0002,3.4e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,7.7e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 +14090000,0.7,0.00052,-0.014,0.71,0.0024,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,-6.8e-05,-0.00032,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0002,0.0002,3.4e-05,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,7.6e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 +14190000,0.7,0.00042,-0.014,0.71,0.0058,0.00063,-0.033,0.0068,-0.0016,-3.7e+02,-0.0011,-0.006,-5.4e-05,-0.00031,0.00088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,7.5e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 +14290000,0.7,0.00043,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,-4.2e-05,-0.00037,0.00095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,7.4e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 +14390000,0.7,0.00035,-0.014,0.71,0.0084,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-0.0011,-0.006,-1.3e-05,-0.00037,0.0007,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,7.3e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 +14490000,0.7,0.00033,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.001,-3.7e+02,-0.0011,-0.006,-2.8e-06,-0.00032,0.00066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,7.3e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 +14590000,0.7,0.00032,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,4.3e-07,-0.00069,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,7.2e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 +14690000,0.7,0.00028,-0.013,0.71,0.0062,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,2.3e-05,-0.00079,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,7.1e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 +14790000,0.7,0.0003,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0012,-0.0061,3.1e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,7e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 +14890000,0.7,0.0003,-0.013,0.71,0.0045,-0.0016,-0.033,0.0041,-0.0036,-3.7e+02,-0.0012,-0.0061,4.6e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.00019,3.4e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,7e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 +14990000,0.7,0.00029,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,4.4e-05,-0.0012,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,6.9e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 +15090000,0.7,0.00022,-0.013,0.71,0.0037,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,4.6e-05,-0.0012,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.8e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 +15190000,0.7,0.00024,-0.013,0.71,0.0031,-0.00078,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,4.5e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.7e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 +15290000,0.7,0.0002,-0.013,0.71,0.0037,-0.00062,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,6.1e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.6e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 +15390000,0.7,0.0002,-0.013,0.71,0.0029,-0.00027,-0.024,0.00055,-0.002,-3.7e+02,-0.0012,-0.0061,9.5e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.6e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 +15490000,0.7,0.00022,-0.013,0.71,0.0042,-0.00065,-0.024,0.00092,-0.0021,-3.7e+02,-0.0012,-0.0061,8e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.5e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 +15590000,0.7,0.00024,-0.013,0.71,0.0023,-0.00064,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,7.1e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.4e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 +15690000,0.7,0.00024,-0.013,0.71,0.0026,-0.00082,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,7.3e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,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.7,0.0002,-0.013,0.71,0.0031,-0.0025,-0.026,-0.00097,-0.0028,-3.7e+02,-0.0012,-0.0061,7.6e-05,-0.0015,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,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.7,0.00015,-0.013,0.71,0.004,-0.003,-0.024,-0.00059,-0.0031,-3.7e+02,-0.0012,-0.0061,8.2e-05,-0.0016,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.2e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0 +15990000,0.7,9.4e-05,-0.013,0.71,0.0039,-0.0039,-0.019,-0.00066,-0.0039,-3.7e+02,-0.0012,-0.0061,0.00011,-0.0019,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.1e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 +16090000,0.7,9.5e-05,-0.013,0.71,0.0056,-0.0041,-0.016,-0.0002,-0.0043,-3.7e+02,-0.0012,-0.0061,0.00014,-0.0019,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 +16190000,0.7,0.00012,-0.013,0.71,0.0056,-0.0033,-0.014,-0.0004,-0.0035,-3.7e+02,-0.0012,-0.0061,0.00015,-0.0018,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 +16290000,0.7,0.00014,-0.013,0.71,0.0072,-0.0041,-0.016,0.00024,-0.0038,-3.7e+02,-0.0012,-0.0061,0.00018,-0.0018,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,5.9e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 +16390000,0.7,0.00013,-0.013,0.71,0.0061,-0.0043,-0.015,-7.4e-05,-0.0031,-3.7e+02,-0.0012,-0.0061,0.00017,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.3e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,5.8e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 +16490000,0.7,0.00015,-0.013,0.71,0.0053,-0.0039,-0.018,0.00047,-0.0035,-3.7e+02,-0.0012,-0.0061,0.00018,-0.0016,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,5.7e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 +16590000,0.7,0.0004,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0025,-7.5e-05,-3.7e+02,-0.0013,-0.006,0.00019,-0.00094,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0 +16690000,0.7,0.00039,-0.013,0.71,0.0019,-0.0007,-0.015,-0.0023,-0.00017,-3.7e+02,-0.0013,-0.006,0.00018,-0.001,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00016,3.3e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,5.6e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 +16790000,0.71,0.00054,-0.013,0.71,-0.0014,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,0.00019,-0.00043,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,5.5e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 +16890000,0.7,0.00055,-0.013,0.71,-0.0017,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-0.0013,-0.006,0.00018,-0.00047,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,5.5e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 +16990000,0.7,0.00049,-0.013,0.71,-0.0017,0.00035,-0.01,-0.0052,0.00086,-3.7e+02,-0.0013,-0.006,0.00017,-0.00088,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,5.4e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17090000,0.7,0.00046,-0.013,0.71,-0.00087,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-0.0013,-0.006,0.00017,-0.00087,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,5.3e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17190000,0.71,0.00045,-0.013,0.71,-0.00042,0.0013,-0.011,-0.0057,-0.00053,-3.7e+02,-0.0014,-0.006,0.00019,-0.0012,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,5.2e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 +17290000,0.7,0.00042,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00036,-3.7e+02,-0.0014,-0.006,0.00017,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,5.2e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 +17390000,0.71,0.00039,-0.013,0.71,0.0023,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-0.0014,-0.006,0.00019,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,5.1e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17490000,0.71,0.00038,-0.013,0.71,0.0029,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,0.0002,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,5e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17590000,0.71,0.00029,-0.013,0.71,0.0041,-8.4e-05,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00021,-0.002,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17690000,0.71,0.00026,-0.013,0.71,0.005,0.00062,0.0019,-0.0033,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00022,-0.002,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,4.9e-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.00035,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00025,-0.0019,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,4.8e-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.0091,-0.00041,0.00069,-0.0013,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0019,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,4.8e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0021,0.0019,-0.00056,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,4.7e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0 +18090000,0.71,0.00013,-0.013,0.71,0.011,-0.0023,0.0043,0.00056,-0.0021,-3.7e+02,-0.0013,-0.0061,0.00025,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00014,0.00014,3.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,4.7e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 +18190000,0.71,9.9e-05,-0.013,0.71,0.012,-0.0012,0.0056,0.0014,-0.0017,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0018,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,4.6e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 +18290000,0.71,4e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0026,-0.0018,-3.7e+02,-0.0013,-0.0061,0.00026,-0.0018,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00013,0.00013,3.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,4.5e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 +18390000,0.71,5.5e-05,-0.013,0.71,0.013,-0.00016,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00013,0.00013,3.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 +18490000,0.71,7.1e-05,-0.012,0.71,0.014,0.00025,0.0076,0.0046,-0.0014,-3.7e+02,-0.0013,-0.0061,0.00029,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00013,0.00013,3.3e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,4.4e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 +18590000,0.71,7.6e-05,-0.012,0.71,0.013,0.00049,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.0061,0.00032,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,4.3e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 +18690000,0.71,4.4e-05,-0.012,0.71,0.014,-0.0002,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.0061,0.00031,-0.0017,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00013,0.00013,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,4.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 +18790000,0.71,7.4e-05,-0.012,0.71,0.012,0.0001,0.0035,0.0037,-0.0009,-3.7e+02,-0.0014,-0.0061,0.00031,-0.0017,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,4.2e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 +18890000,0.71,9.8e-05,-0.012,0.71,0.013,0.0006,0.0042,0.005,-0.00083,-3.7e+02,-0.0014,-0.0061,0.00033,-0.0017,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,4.2e-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.00069,-3.7e+02,-0.0014,-0.0061,0.00035,-0.0017,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,4.1e-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.0059,0.0077,-0.00048,-3.7e+02,-0.0014,-0.0061,0.00035,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,4.1e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 +19190000,0.71,7.2e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0085,-0.00044,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.2e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,4e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 +19290000,0.71,9.4e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00025,-3.7e+02,-0.0014,-0.0061,0.00035,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.2e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,4e-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.012,0.00042,0.012,0.008,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,3.9e-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.00029,0.0088,0.0092,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00039,-0.0018,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,3.8e-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.0074,-0.00028,-3.7e+02,-0.0014,-0.0061,0.00041,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,3.8e-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.00053,-3.7e+02,-0.0014,-0.0061,0.0004,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,3.7e-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.0076,-0.0043,0.01,0.0068,-0.00043,-3.7e+02,-0.0014,-0.0061,0.00041,-0.0018,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,3.7e-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.0046,0.011,0.0075,-0.00089,-3.7e+02,-0.0014,-0.0061,0.00044,-0.0018,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,3.6e-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.0039,-0.0053,0.014,0.0061,-0.00074,-3.7e+02,-0.0014,-0.006,0.00047,-0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20090000,0.71,0.00017,-0.012,0.71,0.0037,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,0.00051,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,3.5e-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,0.00052,-0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,3.5e-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.00026,-0.0095,0.015,0.0043,-0.0019,-3.7e+02,-0.0014,-0.006,0.00054,-0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20390000,0.71,0.00026,-0.012,0.71,-0.0022,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,0.00054,-0.0015,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20490000,0.71,0.00031,-0.012,0.71,-0.0027,-0.011,0.016,0.0021,-0.0026,-3.7e+02,-0.0014,-0.006,0.00053,-0.0015,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20590000,0.71,0.00033,-0.012,0.71,-0.0023,-0.011,0.013,0.0018,-0.0021,-3.7e+02,-0.0014,-0.006,0.00052,-0.0013,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20690000,0.71,0.00036,-0.012,0.71,-0.0023,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,0.00053,-0.0013,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20790000,0.71,0.00039,-0.012,0.71,-0.0034,-0.011,0.015,0.0013,-0.0025,-3.7e+02,-0.0014,-0.006,0.00054,-0.0011,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,3.2e-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.0039,-0.014,0.014,0.00097,-0.0038,-3.7e+02,-0.0014,-0.006,0.00056,-0.0011,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20990000,0.71,0.00038,-0.012,0.71,-0.0041,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,0.00056,-0.0009,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.8e-05,3.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,3.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21090000,0.71,0.00038,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,0.00058,-0.0009,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.9e-05,3.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,3.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21190000,0.71,0.00042,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,0.00057,-0.00066,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.7e-05,9.7e-05,3.1e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.71,0.00046,-0.012,0.71,-0.004,-0.018,0.016,0.0033,-0.0054,-3.7e+02,-0.0014,-0.006,0.0006,-0.00066,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.8e-05,9.8e-05,3.1e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.71,0.0005,-0.012,0.71,-0.0048,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,0.00058,-0.00028,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.6e-05,9.6e-05,3.1e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.71,0.00051,-0.012,0.71,-0.0054,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,0.00059,-0.00029,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.7e-05,9.7e-05,3.1e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.71,0.00053,-0.012,0.71,-0.0059,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,0.00059,6.5e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.5e-05,3.1e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21690000,0.71,0.00054,-0.012,0.71,-0.0058,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,0.0006,6.3e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.6e-05,9.5e-05,3.1e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.71,0.00056,-0.012,0.71,-0.0064,-0.011,0.015,4.2e-05,-0.00076,-3.7e+02,-0.0014,-0.0059,0.00058,0.00059,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.4e-05,3.1e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.71,0.00056,-0.012,0.71,-0.0064,-0.012,0.016,-0.0006,-0.0019,-3.7e+02,-0.0014,-0.0059,0.00058,0.00058,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.4e-05,3e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.2e-06,1.3e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.71,0.00061,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,0.00058,0.001,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22090000,0.71,0.00063,-0.012,0.71,-0.0072,-0.0082,0.015,-0.0022,0.00062,-3.7e+02,-0.0014,-0.0059,0.00058,0.001,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.3e-05,3e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22190000,0.71,0.0006,-0.012,0.71,-0.007,-0.0073,0.015,-0.0018,0.00058,-3.7e+02,-0.0014,-0.0059,0.00058,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22290000,0.71,0.00064,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.0002,-3.7e+02,-0.0014,-0.0059,0.00057,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.3e-05,9.3e-05,3e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22390000,0.71,0.00061,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.00019,-3.7e+02,-0.0014,-0.0059,0.00058,0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22490000,0.71,0.00062,-0.012,0.71,-0.0096,-0.0075,0.018,-0.0031,-0.00096,-3.7e+02,-0.0014,-0.0059,0.00058,0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.2e-05,9.2e-05,3e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22590000,0.71,0.0006,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00013,-3.7e+02,-0.0014,-0.0059,0.00058,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22690000,0.71,0.00063,-0.012,0.71,-0.011,-0.0067,0.018,-0.0044,-0.00056,-3.7e+02,-0.0014,-0.0059,0.00059,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.1e-05,9.1e-05,3e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00045,-3.7e+02,-0.0014,-0.0059,0.00056,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.00099,-3.7e+02,-0.0014,-0.0059,0.00055,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00087,-3.7e+02,-0.0014,-0.0059,0.00056,0.0015,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23090000,0.71,0.00058,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,0.00054,0.0015,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,2.9e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23190000,0.71,0.00064,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00054,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,0.00054,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,0.00054,0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,2.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,0.00055,0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.9e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,2.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.0076,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00054,0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.8e-05,8.8e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,2.2e-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.0024,-3.7e+02,-0.0014,-0.0059,0.00054,0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.8e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23790000,0.71,0.005,0.00065,0.71,-0.089,-0.027,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,0.00054,0.002,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,2.2e-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.036,-0.2,-0.031,-0.005,-3.7e+02,-0.0014,-0.0059,0.00053,0.002,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-0.0014,-0.0059,0.00054,0.0022,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.6e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,0.00055,0.0022,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-07,6.7e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,0.00055,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-0.0014,-0.0059,0.00054,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24390000,0.71,0.0038,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0013,-0.0059,0.00053,0.0021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-0.0013,-0.0059,0.00053,0.0021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,0.00054,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,0.00054,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.5e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,0.00053,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.4e-05,8.4e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,0.00052,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.4e-05,8.4e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,0.00051,0.0033,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.3e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.4e-07,5.4e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,0.0005,0.0034,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.4e-05,8.3e-05,2.8e-05,0.018,0.017,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,0.0005,0.003,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-07,5.2e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,0.0005,0.003,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.3e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,0.0005,0.0032,-0.0003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,0.00051,0.0032,-0.00028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,0.00051,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,0.00051,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,1.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,0.00052,0.0037,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,0.00053,0.0036,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,8.1e-05,8e-05,2.7e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,0.00053,0.0032,-0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,8e-05,8e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-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,0.00051,0.0033,-0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-07,4.6e-07,1.7e-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.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,0.00051,0.0044,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.6e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-07,4.4e-07,1.6e-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,0.00051,0.0044,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.6e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-07,4.5e-07,1.6e-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.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,0.00051,0.0031,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.8e-05,2.6e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-07,4.3e-07,1.6e-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,0.00051,0.0031,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.8e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-07,4.3e-07,1.6e-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.00095,-0.0059,0.00048,0.0041,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.7e-05,2.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-07,4.2e-07,1.6e-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.00095,-0.0059,0.00049,0.004,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.7e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-07,4.2e-07,1.6e-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.73,-1.3,-1,-0.85,-3.7e+02,-0.0009,-0.006,0.00047,0.0018,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.1e-07,4.1e-07,1.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-0.0009,-0.006,0.00048,0.0017,-0.016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4.1e-07,4.1e-07,1.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-0.00079,-0.006,0.00047,0.0026,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 +27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-0.00079,-0.006,0.00047,0.0026,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4e-07,4e-07,1.5e-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.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00048,0.0037,-0.021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.6e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.045,0.045,0.035,4e-07,4e-07,1.5e-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.00048,0.0036,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.049,0.049,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 +27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00072,-0.0059,0.00049,0.0057,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.6e-05,0.017,0.017,0.0081,0.052,0.052,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 +27490000,0.71,0.031,0.062,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-0.00072,-0.0059,0.00048,0.0056,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 +27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-0.00075,-0.0059,0.00049,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.059,0.059,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 +27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00075,-0.0059,0.00048,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.7e-05,2.6e-05,0.019,0.019,0.0082,0.065,0.065,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 +27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-0.00075,-0.0058,0.00047,0.0057,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.067,0.067,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 +27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-0.00075,-0.0058,0.00047,0.0055,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0083,0.074,0.073,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 +27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-0.00079,-0.0058,0.00048,0.005,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.5e-05,0.019,0.019,0.0083,0.076,0.076,0.035,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 +28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-0.00079,-0.0058,0.00046,0.005,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.083,0.082,0.035,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 +28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-0.00082,-0.0058,0.00046,0.0046,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 +28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.089,-4.4,-2.4,-3.7e+02,-0.00082,-0.0058,0.00044,0.0045,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.5e-05,0.02,0.02,0.0086,0.092,0.092,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 +28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-0.00082,-0.0058,0.00043,0.0043,-0.015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.7e-05,2.5e-05,0.021,0.021,0.0087,0.099,0.099,0.036,3.7e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 +28490000,0.71,0.0026,0.0044,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-0.00082,-0.0058,0.00042,0.004,-0.014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.5e-05,0.022,0.022,0.0088,0.11,0.11,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 +28590000,0.71,0.00081,0.00092,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-0.00082,-0.0058,0.00042,0.0036,-0.013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.5e-05,0.023,0.024,0.0089,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 +28690000,0.71,0.0001,4.5e-06,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-0.00082,-0.0058,0.00042,0.0032,-0.012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.5e-05,0.025,0.025,0.009,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 +28790000,0.71,-0.00019,-0.00023,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-0.00089,-0.0058,0.00041,0.00015,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.4e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 +28890000,0.71,-0.0002,-1.5e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-0.00089,-0.0058,0.00041,-0.00028,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.4e-05,0.025,0.025,0.009,0.14,0.14,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 +28990000,0.71,-9.5e-06,0.00044,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-0.00098,-0.0058,0.0004,-0.0023,-0.026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.6e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 +29090000,0.71,0.00014,0.00085,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-0.00098,-0.0058,0.00039,-0.0028,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 +29190000,0.71,0.00036,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-0.001,-0.0058,0.0004,-0.0047,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29290000,0.71,0.00072,0.0021,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-0.001,-0.0058,0.00039,-0.0053,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.025,0.0091,0.16,0.16,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29390000,0.71,0.0013,0.0036,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-0.0011,-0.0058,0.00037,-0.0068,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.16,0.16,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 +29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-0.0011,-0.0058,0.00036,-0.0073,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-0.0011,-0.0057,0.00036,-0.0096,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.025,0.009,0.17,0.17,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-0.0011,-0.0057,0.00035,-0.01,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-07,3.5e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.94,-8.5,-4.1,-3.7e+02,-0.0012,-0.0057,0.00035,-0.012,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +29890000,0.71,0.0029,0.0073,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-0.0012,-0.0057,0.00033,-0.013,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +29990000,0.71,0.003,0.0075,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-0.0012,-0.0057,0.00032,-0.015,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.18,0.18,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-0.0012,-0.0057,0.00031,-0.015,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-0.0013,-0.0057,0.00031,-0.016,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.19,0.19,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-0.0013,-0.0057,0.0003,-0.017,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.8e-05,2.3e-05,0.026,0.026,0.0091,0.21,0.21,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30390000,0.71,0.003,0.007,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-0.0013,-0.0057,0.00029,-0.018,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.2,0.2,0.036,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-0.0013,-0.0057,0.0003,-0.018,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.026,0.026,0.0091,0.22,0.22,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-0.0013,-0.0057,0.0003,-0.019,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-0.0013,-0.0057,0.00029,-0.02,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.23,0.23,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-0.0013,-0.0057,0.00028,-0.02,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30890000,0.71,0.0025,0.0054,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0057,0.00028,-0.021,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.24,0.24,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30990000,0.71,0.0024,0.005,0.71,-1.9,-0.96,0.76,-11,-5.3,-3.7e+02,-0.0013,-0.0057,0.00027,-0.022,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-0.0013,-0.0057,0.00026,-0.022,-0.018,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.25,0.25,0.037,3.1e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31190000,0.71,0.0022,0.0042,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-0.0014,-0.0057,0.00026,-0.023,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31290000,0.71,0.002,0.0037,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-0.0014,-0.0057,0.00026,-0.024,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.0089,0.25,0.25,0.037,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31390000,0.71,0.0018,0.0032,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-0.0014,-0.0057,0.00025,-0.025,-0.013,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-07,3.1e-07,9.8e-07,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31490000,0.71,0.0016,0.0026,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00024,-0.025,-0.011,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.26,0.26,0.037,3.1e-07,3.1e-07,9.7e-07,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00024,-0.026,-0.0095,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3e-07,3e-07,9.6e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31690000,0.71,0.0013,0.0016,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-0.0014,-0.0057,0.00024,-0.027,-0.0083,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.2e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3e-07,3e-07,9.5e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31790000,0.71,0.0011,0.001,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0065,-0.098,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.2e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-07,3e-07,9.4e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31890000,0.71,0.00087,0.00033,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0051,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.2e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-07,3e-07,9.4e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31990000,0.71,0.00074,-0.00013,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-0.0014,-0.0057,0.00023,-0.029,-0.0032,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32090000,0.71,0.00045,-0.00085,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0057,0.00022,-0.03,-0.0017,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-07,3e-07,9.2e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.031,0.00036,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-07,2.9e-07,9.1e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32290000,0.71,1.1e-05,-0.0024,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.031,0.002,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.3,0.3,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32390000,0.71,-0.00017,-0.003,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.0029,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.004,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-07,2.9e-07,8.9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0048,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.5e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.9e-07,2.9e-07,8.8e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0053,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-07,2.9e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32790000,0.71,-0.00029,-0.0035,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0063,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.8e-07,2.8e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-0.0015,-0.0057,0.00018,-0.034,0.0073,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.8e-07,2.9e-07,8.6e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32990000,0.71,-7.3e-05,-0.0034,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-0.0015,-0.0057,0.00019,-0.034,0.0087,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.024,0.0083,0.32,0.32,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33090000,0.71,-0.00011,-0.0034,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0092,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0099,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.2e-05,8.1e-05,7.4e-05,2.1e-05,0.024,0.024,0.0083,0.33,0.33,0.036,2.8e-07,2.8e-07,8.4e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.4e-05,1.8e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-07,2.8e-07,8.3e-07,0.027,0.025,0.0005,0.0025,9.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33390000,0.55,0.013,-0.0018,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.9e-05,7.5e-05,1.4e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-07,2.8e-07,8.3e-07,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33490000,0.41,0.0068,0.00068,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,7.8e-05,7.7e-05,1.1e-05,0.026,0.026,0.0081,0.35,0.35,0.036,2.8e-07,2.8e-07,8.2e-07,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33590000,0.25,0.00096,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,7.6e-05,7.8e-05,1.1e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.7e-07,2.8e-07,8.1e-07,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.5e-05,8e-05,1.3e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.7e-07,2.8e-07,8.1e-07,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,7.2e-05,8e-05,1.8e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-07,2.7e-07,8e-07,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33890000,-0.25,-0.005,-0.0075,0.97,-1,-0.66,0.77,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,4.7e-05,7.2e-05,8.1e-05,2.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-07,2.7e-07,7.9e-07,0.027,0.025,0.0005,0.0025,8.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33990000,-0.39,-0.0032,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0056,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,6.9e-05,7.8e-05,3.1e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-07,2.7e-07,7.9e-07,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0056,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,6.9e-05,7.8e-05,3.6e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34190000,-0.57,-0.0014,-0.011,0.82,-0.91,-0.54,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,0.00022,-0.038,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,6.5e-05,7.3e-05,3.9e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34290000,-0.61,-0.0024,-0.0085,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-0.0015,-0.0057,0.00022,-0.038,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,6.5e-05,7.3e-05,4e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-07,2.7e-07,7.7e-07,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34390000,-0.64,-0.0025,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.018,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,6e-05,6.7e-05,4.1e-05,0.041,0.043,0.0065,0.39,0.39,0.035,2.6e-07,2.7e-07,7.7e-07,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.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.018,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,6.1e-05,6.7e-05,4.1e-05,0.048,0.05,0.0064,0.4,0.4,0.035,2.7e-07,2.7e-07,7.6e-07,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.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,5.5e-05,6.1e-05,4e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-07,2.6e-07,7.6e-07,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.36,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.5e-05,6.1e-05,4e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.6e-07,2.7e-07,7.6e-07,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.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.064,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.9e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-07,2.6e-07,7.5e-07,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34890000,-0.68,-0.0021,-0.0016,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.064,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.8e-05,0.058,0.061,0.0062,0.42,0.42,0.034,2.6e-07,2.7e-07,7.5e-07,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34990000,-0.68,-0.0085,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.7e-05,0.056,0.058,0.0068,0.41,0.42,0.034,2.6e-07,2.6e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.7e-05,0.061,0.063,0.0068,0.43,0.43,0.034,2.6e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35190000,-0.68,-0.0085,-0.0045,0.73,0.46,0.34,-0.18,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.6e-05,0.066,0.068,0.0067,0.44,0.44,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.071,0.074,0.0066,0.45,0.45,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35390000,-0.68,-0.0086,-0.0045,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.4e-05,0.077,0.08,0.0066,0.47,0.47,0.034,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35490000,-0.68,-0.0087,-0.0045,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.4e-05,0.083,0.087,0.0065,0.49,0.49,0.034,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35590000,-0.68,-0.0056,-0.0045,0.73,0.42,0.36,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35690000,-0.68,-0.0056,-0.0045,0.73,0.44,0.38,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.072,0.075,0.0061,0.49,0.49,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35790000,-0.68,-0.0034,-0.0044,0.73,0.36,0.32,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00027,-0.079,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.3e-05,3.6e-05,3.2e-05,0.06,0.062,0.0059,0.48,0.48,0.033,2.7e-07,2.7e-07,7.2e-07,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35890000,-0.68,-0.0034,-0.0045,0.73,0.38,0.35,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00028,-0.079,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.3e-05,3.6e-05,3.1e-05,0.066,0.068,0.0058,0.5,0.5,0.033,2.7e-07,2.7e-07,7.2e-07,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35990000,-0.68,-0.0015,-0.0044,0.73,0.31,0.29,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0003,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,2.9e-05,3.1e-05,3.1e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-07,2.7e-07,7.2e-07,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36090000,-0.68,-0.0016,-0.0044,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00031,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-07,2.7e-07,7.2e-07,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36190000,-0.68,-0.00018,-0.0043,0.73,0.27,0.27,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00032,-0.098,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.6e-05,2.8e-05,3e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-07,2.7e-07,7.1e-07,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36290000,-0.68,-0.0003,-0.0042,0.73,0.28,0.29,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00033,-0.098,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.6e-05,2.8e-05,2.9e-05,0.06,0.062,0.0056,0.51,0.51,0.032,2.7e-07,2.8e-07,7.1e-07,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36390000,-0.68,0.00075,-0.0041,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00034,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-07,2.8e-07,7.1e-07,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36490000,-0.68,0.00066,-0.0042,0.73,0.24,0.26,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00036,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.8e-05,0.059,0.061,0.0055,0.52,0.52,0.032,2.8e-07,2.8e-07,7.1e-07,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36590000,-0.68,0.0014,-0.004,0.73,0.2,0.22,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00037,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-07,2.8e-07,7.1e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36690000,-0.68,0.0014,-0.004,0.73,0.2,0.24,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00038,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36790000,-0.68,0.002,-0.0039,0.73,0.17,0.21,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00039,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36890000,-0.68,0.0019,-0.0039,0.74,0.17,0.22,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0004,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36990000,-0.68,0.0024,-0.0037,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00041,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,1.9e-05,2e-05,2.7e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7e-07,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37090000,-0.68,0.0023,-0.0037,0.74,0.14,0.19,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00043,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,1.9e-05,2e-05,2.6e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7e-07,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37190000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00044,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,6.9e-07,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37290000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00045,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.055,0.057,0.0058,0.56,0.56,0.031,2.8e-07,2.9e-07,6.9e-07,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37390000,-0.68,0.0028,-0.0035,0.74,0.097,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00046,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,6.9e-07,0.02,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37490000,-0.68,0.0028,-0.0034,0.74,0.096,0.15,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00047,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-07,2.9e-07,6.9e-07,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37590000,-0.68,0.0029,-0.0033,0.74,0.077,0.13,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00048,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.5e-05,0.049,0.049,0.0061,0.57,0.57,0.031,2.9e-07,2.9e-07,6.9e-07,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37690000,-0.68,0.0029,-0.0034,0.74,0.075,0.14,-0.11,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00049,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.4e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-07,2.9e-07,6.9e-07,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37790000,-0.68,0.003,-0.0033,0.74,0.059,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00051,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.7e-05,1.8e-05,2.4e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-07,2.9e-07,6.8e-07,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37890000,-0.68,0.003,-0.0033,0.74,0.056,0.12,-0.093,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00052,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.7e-05,1.8e-05,2.4e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-07,2.9e-07,6.8e-07,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37990000,-0.68,0.003,-0.0033,0.74,0.042,0.1,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00053,-0.2,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.7e-05,1.8e-05,2.4e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-07,2.9e-07,6.8e-07,0.017,0.016,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38090000,-0.68,0.003,-0.0033,0.74,0.038,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00054,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-07,2.9e-07,6.8e-07,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38190000,-0.68,0.003,-0.0032,0.74,0.025,0.089,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00055,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-07,2.9e-07,6.8e-07,0.016,0.015,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38290000,-0.68,0.003,-0.0032,0.74,0.022,0.09,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00056,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-07,2.9e-07,6.8e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38390000,-0.68,0.003,-0.0032,0.74,0.013,0.078,-0.051,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00058,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-07,3e-07,6.8e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38490000,-0.68,0.003,-0.0032,0.74,0.01,0.079,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00059,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-07,3e-07,6.7e-07,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38590000,-0.68,0.003,-0.0031,0.74,0.0054,0.068,-0.037,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0006,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-07,3e-07,6.7e-07,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38690000,-0.68,0.0029,-0.0031,0.74,0.001,0.068,-0.03,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00061,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-07,3e-07,6.7e-07,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38790000,-0.68,0.0029,-0.003,0.74,-0.0041,0.056,-0.022,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00062,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-07,3e-07,6.7e-07,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38890000,-0.68,0.0027,-0.0031,0.74,-0.014,0.045,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00063,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.8e-05,1.8e-05,2.2e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-07,3e-07,6.7e-07,0.014,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 b1b2ffde82..4655da8938 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -1,351 +1,351 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.8e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.8e-07,0.0025,0.0025,0.005,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -90000,0.98,-0.0095,-0.012,0.18,-5.5e-05,-0.0032,-0.024,-3.6e-06,-0.00014,-0.0021,0,0,0,0,0,0,0.2,-4.7e-10,0.43,0,0,0,0,0,9e-07,0.0026,0.0026,0.0051,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -190000,0.98,-0.0091,-0.013,0.21,-0.0013,-0.0036,-0.037,-4.4e-05,-0.00046,-0.017,5.2e-10,-4.3e-10,-3e-12,0,0,-6.8e-08,0.2,0.012,0.43,0,0,0,0,0,2.9e-06,0.0027,0.0027,0.0052,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -290000,0.98,-0.0092,-0.013,0.21,-0.0016,-0.0053,-0.046,-0.00015,-0.00032,-0.018,4.4e-09,-5.5e-09,1.1e-11,0,0,-2.9e-06,0.2,0.012,0.43,0,0,0,0,0,7.1e-06,0.0029,0.0029,0.0054,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -390000,0.98,-0.0095,-0.013,0.19,-0.00033,-0.0065,-0.063,-0.00029,-0.00087,-0.013,-6.7e-09,-6.3e-09,-1.6e-10,0,0,8.8e-06,0.2,0.002,0.44,0,0,0,0,0,1.3e-05,0.0031,0.0031,0.0056,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -490000,0.98,-0.0095,-0.014,0.19,0.0016,-0.0061,-0.069,2.4e-05,-0.00049,-0.011,-1.2e-06,6.5e-07,4.2e-08,0,0,1.6e-05,0.2,0.002,0.44,0,0,0,0,0,2e-05,0.0034,0.0034,0.0058,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -590000,0.98,-0.0095,-0.014,0.19,0.0014,-0.0091,-0.12,0.00018,-0.0013,-0.029,-1.4e-06,6.7e-07,4.3e-08,0,0,6.4e-05,0.2,0.002,0.44,0,0,0,0,0,2.9e-05,0.0037,0.0037,0.0062,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -690000,0.98,-0.0096,-0.014,0.19,0.0032,-0.0083,-0.05,0.00021,-0.00076,-0.0088,-5.6e-06,1.3e-06,1.6e-07,0,0,-9.5e-05,0.2,0.002,0.44,0,0,0,0,0,4e-05,0.004,0.004,0.0065,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -790000,0.98,-0.0096,-0.014,0.19,0.0059,-0.009,-0.054,0.0006,-0.0016,-0.011,-5.5e-06,1.3e-06,1.6e-07,0,0,-0.00013,0.2,0.002,0.44,0,0,0,0,0,5.3e-05,0.0044,0.0044,0.0069,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -890000,0.98,-0.0096,-0.015,0.19,0.006,-0.0068,-0.093,0.00052,-0.00095,-0.031,-2.2e-05,1.6e-07,4.9e-07,0,0,-3.3e-05,0.2,0.002,0.44,0,0,0,0,0,6.7e-05,0.0048,0.0048,0.0074,1.3,1.3,1.3,0.2,0.2,0.25,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -990000,0.98,-0.0096,-0.015,0.19,0.0091,-0.0071,-0.12,0.0013,-0.0017,-0.046,-2.2e-05,1.2e-07,4.9e-07,0,0,1.3e-05,0.2,0.002,0.44,0,0,0,0,0,8.3e-05,0.0053,0.0053,0.0079,1.5,1.5,0.95,0.3,0.3,0.23,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1090000,0.98,-0.0096,-0.015,0.19,0.015,-0.0083,-0.13,0.0012,-0.0011,-0.062,-6.1e-05,-1.7e-05,9.8e-07,0,0,4.5e-05,0.2,0.002,0.44,0,0,0,0,0,0.0001,0.0057,0.0057,0.0084,0.92,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1190000,0.98,-0.0096,-0.015,0.19,0.021,-0.011,-0.11,0.003,-0.0021,-0.047,-5.8e-05,-1.5e-05,9.8e-07,0,0,-0.00048,0.2,0.002,0.44,0,0,0,0,0,0.00012,0.0063,0.0063,0.009,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1290000,0.98,-0.0093,-0.016,0.19,0.024,-0.0097,-0.11,0.0027,-0.0016,-0.048,-0.00017,-0.0001,1.5e-06,0,0,-0.00075,0.2,0.002,0.44,0,0,0,0,0,0.00014,0.0064,0.0064,0.0097,0.88,0.88,0.41,0.15,0.15,0.18,0.0095,0.0095,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1390000,0.98,-0.0093,-0.016,0.19,0.033,-0.012,-0.097,0.0056,-0.0027,-0.038,-0.00016,-9.6e-05,1.5e-06,0,0,-0.0014,0.2,0.002,0.44,0,0,0,0,0,0.00016,0.0071,0.0071,0.01,1.1,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1490000,0.98,-0.009,-0.016,0.19,0.03,-0.01,-0.12,0.0044,-0.0018,-0.053,-0.00039,-0.00034,1.2e-06,0,0,-0.0012,0.2,0.002,0.44,0,0,0,0,0,0.00019,0.0067,0.0067,0.011,0.95,0.95,0.27,0.14,0.14,0.15,0.0089,0.0089,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1590000,0.98,-0.0091,-0.016,0.19,0.037,-0.012,-0.13,0.0077,-0.003,-0.063,-0.00039,-0.00034,1.2e-06,0,0,-0.0014,0.2,0.002,0.44,0,0,0,0,0,0.00022,0.0074,0.0074,0.012,1.3,1.3,0.23,0.2,0.2,0.14,0.0089,0.0089,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1690000,0.98,-0.0088,-0.016,0.19,0.033,-0.0083,-0.13,0.0054,-0.0019,-0.068,-0.00073,-0.00075,-3.2e-07,0,0,-0.0018,0.2,0.002,0.44,0,0,0,0,0,0.00024,0.0064,0.0064,0.013,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -1790000,0.98,-0.009,-0.016,0.19,0.042,-0.0099,-0.13,0.0092,-0.0029,-0.067,-0.00073,-0.00074,-2.5e-07,0,0,-0.0028,0.2,0.002,0.44,0,0,0,0,0,0.00027,0.007,0.007,0.014,1.3,1.3,0.16,0.2,0.2,0.12,0.0078,0.0078,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -1890000,0.98,-0.0089,-0.016,0.19,0.049,-0.0086,-0.14,0.014,-0.0037,-0.075,-0.00072,-0.00074,-2.1e-07,0,0,-0.0032,0.2,0.002,0.44,0,0,0,0,0,0.0003,0.0076,0.0076,0.015,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -1990000,0.98,-0.0085,-0.016,0.19,0.039,-0.0042,-0.14,0.0096,-0.0021,-0.074,-0.0011,-0.0013,-3.5e-06,0,0,-0.0046,0.2,0.002,0.44,0,0,0,0,0,0.00034,0.0061,0.0061,0.016,1.3,1.3,0.13,0.2,0.2,0.11,0.0066,0.0066,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -2090000,0.98,-0.0086,-0.016,0.19,0.046,-0.0041,-0.14,0.014,-0.0026,-0.071,-0.0011,-0.0013,-3.3e-06,0,0,-0.0065,0.2,0.002,0.44,0,0,0,0,0,0.00037,0.0066,0.0066,0.017,1.7,1.7,0.12,0.31,0.31,0.11,0.0066,0.0066,0.01,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -2190000,0.98,-0.0082,-0.015,0.19,0.035,-0.0012,-0.14,0.0091,-0.0012,-0.077,-0.0014,-0.0018,-8.5e-06,0,0,-0.0075,0.2,0.002,0.44,0,0,0,0,0,0.00041,0.005,0.005,0.018,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,0.01,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -2290000,0.98,-0.0082,-0.016,0.19,0.04,8.5e-05,-0.14,0.013,-0.0012,-0.075,-0.0014,-0.0018,-8.3e-06,0,0,-0.0098,0.2,0.002,0.44,0,0,0,0,0,0.00045,0.0054,0.0054,0.019,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,0.01,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -2390000,0.98,-0.008,-0.015,0.19,0.031,0.0011,-0.14,0.0082,-0.00046,-0.072,-0.0017,-0.0023,-1.4e-05,0,0,-0.012,0.2,0.002,0.44,0,0,0,0,0,0.00049,0.004,0.004,0.02,1,1,0.1,0.19,0.19,0.098,0.0045,0.0045,0.01,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -2490000,0.98,-0.0079,-0.015,0.19,0.033,0.0031,-0.14,0.011,-0.00026,-0.079,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0.2,0.002,0.44,0,0,0,0,0,0.00053,0.0044,0.0044,0.021,1.3,1.3,0.1,0.28,0.28,0.097,0.0045,0.0045,0.01,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -2590000,0.98,-0.0078,-0.015,0.19,0.023,0.0022,-0.15,0.0069,8.6e-05,-0.085,-0.0018,-0.0027,-2e-05,0,0,-0.015,0.2,0.002,0.44,0,0,0,0,0,0.00057,0.0032,0.0032,0.022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,0.01,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -2690000,0.98,-0.0078,-0.015,0.19,0.027,0.0043,-0.15,0.0095,0.00041,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0.2,0.002,0.44,0,0,0,0,0,0.00062,0.0035,0.0035,0.024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,0.01,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -2790000,0.98,-0.0077,-0.015,0.19,0.021,0.0046,-0.14,0.006,0.00052,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0.2,0.002,0.44,0,0,0,0,0,0.00066,0.0027,0.0027,0.025,0.77,0.77,0.096,0.16,0.16,0.089,0.0032,0.0032,0.01,0.04,0.04,0.035,0,0,0,0,0,0,0,0 -2890000,0.98,-0.0077,-0.015,0.19,0.025,0.0043,-0.14,0.0084,0.00092,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.025,0.2,0.002,0.44,0,0,0,0,0,0.00071,0.0029,0.0029,0.027,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,0.01,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -2990000,0.98,-0.0076,-0.015,0.19,0.019,0.0032,-0.15,0.0054,0.00069,-0.086,-0.002,-0.0033,-3e-05,0,0,-0.028,0.2,0.002,0.44,0,0,0,0,0,0.00076,0.0023,0.0023,0.028,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,0.01,0.04,0.04,0.033,0,0,0,0,0,0,0,0 -3090000,0.98,-0.0076,-0.015,0.19,0.026,0.0024,-0.15,0.0077,0.00092,-0.087,-0.002,-0.0033,-2.9e-05,0,0,-0.031,0.2,0.002,0.44,0,0,0,0,0,0.00081,0.0025,0.0025,0.03,0.82,0.82,0.095,0.22,0.22,0.086,0.0027,0.0027,0.01,0.04,0.04,0.032,0,0,0,0,0,0,0,0 -3190000,0.98,-0.0076,-0.015,0.19,0.021,0.001,-0.15,0.0052,0.00052,-0.097,-0.002,-0.0036,-3.4e-05,0,0,-0.033,0.2,0.002,0.44,0,0,0,0,0,0.00087,0.002,0.002,0.031,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,0.01,0.04,0.04,0.031,0,0,0,0,0,0,0,0 -3290000,0.98,-0.0075,-0.015,0.19,0.024,0.0019,-0.15,0.0075,0.00061,-0.11,-0.002,-0.0036,-3.3e-05,0,0,-0.034,0.2,0.002,0.44,0,0,0,0,0,0.00092,0.0022,0.0022,0.033,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,0.01,0.04,0.04,0.03,0,0,0,0,0,0,0,0 -3390000,0.98,-0.0073,-0.014,0.19,0.019,0.0032,-0.15,0.0051,0.00045,-0.1,-0.0021,-0.0038,-3.7e-05,0,0,-0.04,0.2,0.002,0.44,0,0,0,0,0,0.00098,0.0017,0.0017,0.034,0.53,0.53,0.095,0.14,0.14,0.085,0.0019,0.0019,0.01,0.04,0.04,0.029,0,0,0,0,0,0,0,0 -3490000,0.98,-0.0072,-0.014,0.19,0.024,0.0064,-0.15,0.0073,0.00092,-0.1,-0.0021,-0.0038,-3.6e-05,0,0,-0.044,0.2,0.002,0.44,0,0,0,0,0,0.001,0.0019,0.0019,0.036,0.65,0.65,0.095,0.19,0.19,0.086,0.0019,0.0019,0.01,0.04,0.04,0.028,0,0,0,0,0,0,0,0 -3590000,0.98,-0.0071,-0.014,0.19,0.021,0.0056,-0.15,0.0051,0.00081,-0.11,-0.0022,-0.004,-4e-05,0,0,-0.047,0.2,0.002,0.44,0,0,0,0,0,0.0011,0.0015,0.0015,0.038,0.48,0.48,0.094,0.13,0.13,0.086,0.0016,0.0016,0.01,0.04,0.04,0.026,0,0,0,0,0,0,0,0 -3690000,0.98,-0.0071,-0.014,0.19,0.023,0.0071,-0.15,0.0074,0.0014,-0.11,-0.0021,-0.004,-4e-05,0,0,-0.052,0.2,0.002,0.44,0,0,0,0,0,0.0012,0.0017,0.0017,0.04,0.59,0.59,0.093,0.18,0.18,0.085,0.0016,0.0016,0.01,0.04,0.04,0.025,0,0,0,0,0,0,0,0 -3790000,0.98,-0.007,-0.014,0.19,0.018,0.0097,-0.15,0.005,0.0012,-0.11,-0.0022,-0.0042,-4.5e-05,0,0,-0.055,0.2,0.002,0.44,0,0,0,0,0,0.0012,0.0014,0.0014,0.042,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,0.01,0.04,0.04,0.024,0,0,0,0,0,0,0,0 -3890000,0.98,-0.007,-0.014,0.19,0.019,0.011,-0.14,0.0069,0.0023,-0.11,-0.0022,-0.0042,-4.5e-05,0,0,-0.059,0.2,0.002,0.44,0,0,0,0,0,0.0013,0.0015,0.0015,0.043,0.54,0.54,0.091,0.17,0.17,0.086,0.0014,0.0014,0.01,0.04,0.04,0.022,0,0,0,0,0,0,0,0 -3990000,0.98,-0.007,-0.014,0.19,0.023,0.013,-0.14,0.0091,0.0035,-0.11,-0.0022,-0.0042,-4.4e-05,0,0,-0.064,0.2,0.002,0.44,0,0,0,0,0,0.0014,0.0017,0.0017,0.045,0.66,0.66,0.089,0.22,0.22,0.085,0.0014,0.0014,0.01,0.04,0.04,0.021,0,0,0,0,0,0,0,0 -4090000,0.98,-0.0069,-0.014,0.19,0.02,0.011,-0.12,0.0067,0.0028,-0.098,-0.0022,-0.0044,-5e-05,0,0,-0.072,0.2,0.002,0.44,0,0,0,0,0,0.0014,0.0013,0.0013,0.047,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,0.01,0.04,0.04,0.02,0,0,0,0,0,0,0,0 -4190000,0.98,-0.007,-0.014,0.19,0.023,0.011,-0.12,0.0088,0.0039,-0.1,-0.0022,-0.0044,-5e-05,0,0,-0.074,0.2,0.002,0.44,0,0,0,0,0,0.0015,0.0015,0.0015,0.049,0.6,0.6,0.086,0.21,0.21,0.086,0.0012,0.0012,0.01,0.04,0.04,0.019,0,0,0,0,0,0,0,0 -4290000,0.98,-0.0071,-0.014,0.19,0.02,0.01,-0.12,0.0064,0.0029,-0.11,-0.0022,-0.0046,-5.6e-05,0,0,-0.077,0.2,0.002,0.44,0,0,0,0,0,0.0016,0.0012,0.0012,0.052,0.46,0.46,0.084,0.15,0.15,0.085,0.00096,0.00096,0.01,0.04,0.04,0.017,0,0,0,0,0,0,0,0 -4390000,0.98,-0.0071,-0.014,0.19,0.024,0.01,-0.11,0.0087,0.0039,-0.094,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0.2,0.002,0.44,0,0,0,0,0,0.0017,0.0013,0.0013,0.054,0.56,0.56,0.081,0.2,0.2,0.084,0.00096,0.00096,0.01,0.04,0.04,0.016,0,0,0,0,0,0,0,0 -4490000,0.98,-0.0072,-0.014,0.19,0.02,0.01,-0.11,0.0064,0.0029,-0.095,-0.0021,-0.0048,-6.1e-05,0,0,-0.086,0.2,0.002,0.44,0,0,0,0,0,0.0017,0.0011,0.0011,0.056,0.43,0.43,0.08,0.14,0.14,0.085,0.00079,0.00079,0.01,0.04,0.04,0.015,0,0,0,0,0,0,0,0 -4590000,0.98,-0.0071,-0.014,0.19,0.023,0.01,-0.11,0.0085,0.0039,-0.098,-0.0021,-0.0048,-6.1e-05,0,0,-0.089,0.2,0.002,0.44,0,0,0,0,0,0.0018,0.0011,0.0011,0.058,0.51,0.51,0.077,0.19,0.19,0.084,0.00079,0.00079,0.01,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -4690000,0.98,-0.0071,-0.013,0.19,0.017,0.0083,-0.1,0.0062,0.0029,-0.09,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0.2,0.002,0.44,0,0,0,0,0,0.0019,0.00093,0.00092,0.06,0.39,0.39,0.074,0.14,0.14,0.083,0.00065,0.00065,0.01,0.04,0.04,0.013,0,0,0,0,0,0,0,0 -4790000,0.98,-0.007,-0.013,0.19,0.014,0.0094,-0.099,0.0078,0.0038,-0.092,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0.2,0.002,0.44,0,0,0,0,0,0.002,0.001,0.001,0.063,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,0.01,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -4890000,0.98,-0.007,-0.013,0.19,0.01,0.0054,-0.093,0.0052,0.0026,-0.088,-0.0021,-0.0051,-7.1e-05,0,0,-0.099,0.2,0.002,0.44,0,0,0,0,0,0.0021,0.00081,0.00081,0.065,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,0.01,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -4990000,0.98,-0.0069,-0.013,0.19,0.014,0.0072,-0.085,0.0064,0.0033,-0.083,-0.0021,-0.0051,-7.1e-05,0,0,-0.1,0.2,0.002,0.44,0,0,0,0,0,0.0021,0.00088,0.00087,0.068,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,0.01,0.04,0.04,0.01,0,0,0,0,0,0,0,0 -5090000,0.98,-0.0069,-0.013,0.19,0.01,0.0064,-0.082,0.0045,0.0023,-0.081,-0.0021,-0.0052,-7.4e-05,0,0,-0.1,0.2,0.002,0.44,0,0,0,0,0,0.0022,0.00071,0.0007,0.07,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,0.01,0.04,0.04,0.0098,0,0,0,0,0,0,0,0 -5190000,0.98,-0.0067,-0.013,0.19,0.0089,0.0096,-0.08,0.0054,0.0031,-0.079,-0.0021,-0.0052,-7.4e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0023,0.00076,0.00075,0.073,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,0.01,0.04,0.04,0.0091,0,0,0,0,0,0,0,0 -5290000,0.98,-0.0066,-0.013,0.19,0.0071,0.0092,-0.068,0.0037,0.0024,-0.072,-0.0021,-0.0053,-7.7e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0024,0.00061,0.00061,0.075,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,0.01,0.04,0.04,0.0084,0,0,0,0,0,0,0,0 -5390000,0.98,-0.0065,-0.013,0.19,0.0055,0.012,-0.065,0.0044,0.0034,-0.067,-0.0021,-0.0053,-7.7e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0025,0.00066,0.00065,0.078,0.36,0.36,0.057,0.15,0.15,0.079,0.00035,0.00035,0.01,0.04,0.04,0.0078,0,0,0,0,0,0,0,0 -5490000,0.98,-0.0066,-0.013,0.19,0.0043,0.013,-0.06,0.0028,0.0028,-0.065,-0.0021,-0.0054,-8.1e-05,0,0,-0.11,0.2,0.002,0.44,0,0,0,0,0,0.0026,0.00053,0.00053,0.08,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,0.01,0.04,0.04,0.0073,0,0,0,0,0,0,0,0 -5590000,0.98,-0.0066,-0.013,0.19,0.0043,0.017,-0.053,0.0033,0.0044,-0.058,-0.0021,-0.0054,-8.1e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0027,0.00057,0.00056,0.083,0.32,0.32,0.053,0.15,0.15,0.078,0.00028,0.00028,0.01,0.04,0.04,0.0067,0,0,0,0,0,0,0,0 -5690000,0.98,-0.0067,-0.013,0.19,0.0034,0.017,-0.052,0.0022,0.0036,-0.055,-0.002,-0.0054,-8.7e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0028,0.00046,0.00045,0.086,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,0.01,0.04,0.04,0.0062,0,0,0,0,0,0,0,0 -5790000,0.98,-0.0065,-0.013,0.19,0.004,0.02,-0.049,0.0026,0.0054,-0.053,-0.002,-0.0054,-8.7e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0029,0.00049,0.00049,0.089,0.29,0.29,0.05,0.14,0.14,0.077,0.00023,0.00023,0.01,0.04,0.04,0.0058,0,0,0,0,0,0,0,0 -5890000,0.98,-0.0066,-0.013,0.19,0.005,0.018,-0.048,0.0018,0.0044,-0.056,-0.0019,-0.0055,-9.5e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.003,0.0004,0.00039,0.092,0.23,0.23,0.048,0.1,0.1,0.075,0.00019,0.00019,0.01,0.04,0.04,0.0054,0,0,0,0,0,0,0,0 -5990000,0.98,-0.0065,-0.013,0.19,0.0061,0.019,-0.041,0.0024,0.0062,-0.05,-0.0019,-0.0055,-9.5e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0031,0.00043,0.00042,0.095,0.27,0.27,0.045,0.13,0.13,0.074,0.00019,0.00019,0.01,0.04,0.04,0.005,0,0,0,0,0,0,0,0 -6090000,0.98,-0.0065,-0.013,0.19,0.0058,0.021,-0.039,0.003,0.0082,-0.047,-0.0019,-0.0055,-9.5e-05,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0032,0.00046,0.00045,0.098,0.31,0.31,0.044,0.17,0.17,0.074,0.00019,0.00019,0.01,0.04,0.04,0.0047,0,0,0,0,0,0,0,0 -6190000,0.98,-0.0066,-0.013,0.19,0.0037,0.019,-0.037,0.0022,0.0066,-0.047,-0.0019,-0.0056,-0.0001,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0033,0.00037,0.00036,0.1,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,0.01,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 -6290000,0.98,-0.0066,-0.013,0.19,0.0022,0.021,-0.041,0.0025,0.0085,-0.053,-0.0019,-0.0056,-0.0001,0,0,-0.12,0.2,0.002,0.44,0,0,0,0,0,0.0034,0.00039,0.00039,0.1,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,0.01,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 -6390000,0.98,-0.0067,-0.013,0.19,0.0032,0.018,-0.042,0.0017,0.0068,-0.056,-0.0018,-0.0056,-0.00015,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.0003,0.0003,0.0035,0.2,0.2,0.039,0.12,0.12,0.072,0.00012,0.00012,0.01,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 -6490000,0.98,-0.0066,-0.013,0.19,0.00096,0.017,-0.039,0.0019,0.0085,-0.053,-0.0018,-0.0056,-0.00054,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.0003,0.0003,0.0015,0.21,0.21,0.038,0.15,0.15,0.07,0.00012,0.00012,0.0099,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 -6590000,0.98,-0.0065,-0.013,0.19,0.00025,0.02,-0.042,0.002,0.01,-0.056,-0.0018,-0.0056,-0.00096,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00021,0.0003,0.0003,0.001,0.21,0.21,0.036,0.18,0.18,0.069,0.00012,0.00012,0.0098,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 -6690000,0.98,-0.0064,-0.013,0.19,-0.0024,0.022,-0.044,0.0018,0.012,-0.057,-0.0019,-0.0056,-0.0017,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0003,0.0003,0.0008,0.22,0.22,0.035,0.22,0.22,0.068,0.00012,0.00012,0.0096,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 -6790000,0.98,-0.0064,-0.013,0.19,-0.00064,0.024,-0.042,0.0016,0.015,-0.058,-0.0019,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.0003,0.0003,0.00071,0.23,0.24,0.034,0.26,0.26,0.068,0.00012,0.00012,0.0092,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 -6890000,0.98,-0.0062,-0.013,0.19,-0.0011,0.024,-0.038,0.0016,0.017,-0.055,-0.0019,-0.0056,-0.0023,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00066,0.25,0.25,0.032,0.31,0.31,0.067,0.00012,0.00012,0.0087,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 -6990000,0.98,-0.0062,-0.013,0.19,-0.0011,0.026,-0.037,0.0014,0.019,-0.055,-0.0019,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00063,0.27,0.27,0.031,0.36,0.36,0.066,0.00012,0.00012,0.0081,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 -7090000,0.98,-0.0061,-0.012,0.19,-0.002,0.031,-0.037,0.0013,0.022,-0.056,-0.0019,-0.0056,-0.0019,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00031,0.00031,0.00064,0.29,0.29,0.03,0.42,0.42,0.066,0.00012,0.00012,0.0075,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 -7190000,0.98,-0.006,-0.013,0.19,-0.0025,0.034,-0.036,0.00097,0.026,-0.058,-0.0019,-0.0055,-0.0025,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00032,0.00032,0.00063,0.32,0.32,0.029,0.49,0.49,0.065,0.00012,0.00012,0.0067,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 -7290000,0.98,-0.006,-0.013,0.19,-0.0017,0.038,-0.034,0.00073,0.029,-0.054,-0.0019,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00032,0.00032,0.00063,0.35,0.35,0.028,0.56,0.56,0.064,0.00012,0.00012,0.0059,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 -7390000,0.98,-0.0058,-0.013,0.19,-0.0034,0.041,-0.032,0.00052,0.033,-0.052,-0.0019,-0.0056,-0.0016,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00033,0.00033,0.00064,0.38,0.38,0.027,0.64,0.64,0.064,0.00012,0.00012,0.0053,0.04,0.04,0.002,0,0,0,0,0,0,0,0 -7490000,0.98,-0.0058,-0.013,0.19,-0.0011,0.045,-0.026,0.00041,0.038,-0.046,-0.0018,-0.0056,-0.00028,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.00063,0.42,0.42,0.026,0.73,0.73,0.063,0.00012,0.00012,0.0046,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 -7590000,0.98,-0.0059,-0.013,0.19,-9.4e-05,0.048,-0.023,0.00036,0.042,-0.041,-0.0018,-0.0056,-9.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.00061,0.45,0.45,0.025,0.83,0.83,0.062,0.00012,0.00012,0.004,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 -7690000,0.98,-0.0059,-0.013,0.19,-0.00044,0.052,-0.022,0.00033,0.047,-0.036,-0.0018,-0.0056,-0.00028,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.00061,0.5,0.5,0.025,0.95,0.95,0.062,0.00012,0.00012,0.0035,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 -7790000,0.98,-0.0058,-0.013,0.19,0.0012,0.054,-0.024,0.00034,0.052,-0.041,-0.0018,-0.0056,-0.0007,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.00059,0.54,0.54,0.024,1.1,1.1,0.061,0.00012,0.00012,0.003,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 -7890000,0.98,-0.0058,-0.013,0.19,-0.00018,0.059,-0.025,0.0003,0.057,-0.045,-0.0018,-0.0056,-0.00085,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.00057,0.59,0.59,0.023,1.2,1.2,0.06,0.00012,0.00012,0.0026,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 -7990000,0.98,-0.0057,-0.013,0.19,7.8e-05,0.062,-0.021,0.0003,0.062,-0.041,-0.0018,-0.0056,-0.00067,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.00055,0.64,0.64,0.022,1.4,1.4,0.059,0.00012,0.00012,0.0022,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8090000,0.98,-0.0056,-0.013,0.19,0.0016,0.067,-0.022,0.00037,0.069,-0.044,-0.0018,-0.0056,-0.0017,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00038,0.00038,0.00054,0.7,0.7,0.022,1.5,1.5,0.059,0.00012,0.00012,0.002,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8190000,0.98,-0.0056,-0.013,0.19,0.0022,0.073,-0.018,0.00053,0.076,-0.038,-0.0019,-0.0056,-0.0022,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00039,0.00039,0.00052,0.76,0.76,0.021,1.7,1.7,0.058,0.00012,0.00012,0.0017,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 -8290000,0.98,-0.0056,-0.013,0.19,0.0044,0.077,-0.016,0.00085,0.082,-0.038,-0.0018,-0.0056,-0.0021,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.0004,0.0004,0.0005,0.81,0.81,0.02,1.9,1.9,0.057,0.00012,0.00012,0.0015,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8390000,0.98,-0.0056,-0.013,0.19,0.0022,0.08,-0.015,0.0012,0.09,-0.036,-0.0018,-0.0056,-0.0021,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00041,0.00041,0.00049,0.88,0.88,0.02,2.2,2.2,0.057,0.00012,0.00012,0.0013,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8490000,0.98,-0.0055,-0.013,0.19,0.002,0.084,-0.017,0.0014,0.096,-0.041,-0.0018,-0.0056,-0.0014,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00042,0.00042,0.00047,0.94,0.94,0.019,2.4,2.4,0.056,0.00011,0.00011,0.0012,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8590000,0.98,-0.0054,-0.013,0.19,0.0031,0.088,-0.012,0.0016,0.1,-0.036,-0.0018,-0.0056,-0.0015,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00043,0.00043,0.00045,1,1,0.018,2.7,2.7,0.055,0.00011,0.00011,0.001,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8690000,0.98,-0.0055,-0.013,0.19,0.003,0.089,-0.014,0.0019,0.11,-0.037,-0.0018,-0.0056,-0.0013,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00043,0.00043,0.00045,1.1,1.1,0.018,2.9,2.9,0.055,0.00011,0.00011,0.00094,0.04,0.04,0.001,0,0,0,0,0,0,0,0 -8790000,0.98,-0.0054,-0.013,0.19,0.0045,0.093,-0.013,0.0021,0.12,-0.035,-0.0018,-0.0056,-0.0016,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00045,0.00045,0.00043,1.2,1.2,0.018,3.3,3.3,0.055,0.00011,0.00011,0.00084,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 -8890000,0.98,-0.0055,-0.013,0.19,0.0045,0.095,-0.0091,0.0025,0.13,-0.029,-0.0018,-0.0056,-0.0011,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00045,0.00045,0.00041,1.2,1.2,0.017,3.6,3.6,0.054,0.00011,0.00011,0.00075,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 -8990000,0.98,-0.0054,-0.013,0.19,0.0035,0.1,-0.0083,0.0029,0.14,-0.032,-0.0018,-0.0056,-0.00059,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.00041,1.3,1.3,0.017,4,4,0.054,0.00011,0.00011,0.00068,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 -9090000,0.98,-0.0055,-0.013,0.19,0.0038,0.1,-0.0093,0.0032,0.14,-0.032,-0.0017,-0.0056,-8.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.00039,1.3,1.3,0.016,4.2,4.2,0.053,0.00011,0.00011,0.00061,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 -9190000,0.98,-0.0054,-0.013,0.19,0.0073,0.11,-0.0088,0.0037,0.15,-0.032,-0.0017,-0.0056,0.00027,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00038,1.4,1.4,0.016,4.7,4.7,0.052,0.00011,0.00011,0.00055,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 -9290000,0.98,-0.0053,-0.013,0.19,0.0095,0.11,-0.0072,0.0045,0.15,-0.03,-0.0017,-0.0056,0.00036,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00037,1.5,1.5,0.015,5,5,0.052,0.00011,0.00011,0.0005,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 -9390000,0.98,-0.0052,-0.013,0.19,0.0097,0.11,-0.0061,0.0055,0.16,-0.03,-0.0017,-0.0056,-2.3e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00048,0.00048,0.00036,1.6,1.6,0.015,5.5,5.5,0.052,0.00011,0.00011,0.00046,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 -9490000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0044,0.0061,0.17,-0.027,-0.0017,-0.0057,0.00012,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00035,1.6,1.6,0.015,5.8,5.8,0.051,0.0001,0.0001,0.00042,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 -9590000,0.98,-0.0053,-0.013,0.19,0.0094,0.11,-0.0043,0.0069,0.18,-0.028,-0.0017,-0.0056,-0.00045,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00034,1.7,1.7,0.014,6.4,6.4,0.05,0.0001,0.0001,0.00038,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 -9690000,0.98,-0.0054,-0.013,0.19,0.0091,0.11,-0.0014,0.0074,0.18,-0.027,-0.0017,-0.0056,-0.00056,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00033,1.7,1.7,0.014,6.6,6.6,0.05,9.9e-05,0.0001,0.00035,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 -9790000,0.98,-0.0054,-0.013,0.19,0.011,0.11,-0.0027,0.0084,0.19,-0.028,-0.0017,-0.0056,-0.001,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00032,1.8,1.8,0.014,7.3,7.3,0.05,9.9e-05,0.0001,0.00032,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 -9890000,0.98,-0.0054,-0.013,0.19,0.012,0.11,-0.0014,0.0088,0.18,-0.029,-0.0017,-0.0057,-0.00084,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00047,0.00047,0.00031,1.8,1.8,0.013,7.4,7.4,0.049,9.6e-05,9.7e-05,0.0003,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 -9990000,0.98,-0.0054,-0.013,0.19,0.014,0.11,-0.00073,0.01,0.2,-0.031,-0.0017,-0.0057,-0.0011,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00031,1.9,1.9,0.013,8.2,8.2,0.049,9.6e-05,9.7e-05,0.00027,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 -10090000,0.98,-0.0055,-0.013,0.19,0.012,0.11,0.00048,0.011,0.19,-0.029,-0.0016,-0.0057,-0.0014,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00046,0.00046,0.0003,1.9,1.9,0.013,8.2,8.2,0.048,9.3e-05,9.3e-05,0.00025,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 -10190000,0.98,-0.0054,-0.013,0.19,0.011,0.11,0.0014,0.012,0.2,-0.03,-0.0016,-0.0057,-0.0017,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00048,0.00048,0.00029,2,2,0.012,9,9,0.048,9.3e-05,9.3e-05,0.00023,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 -10290000,0.98,-0.0055,-0.013,0.19,0.011,0.11,0.00029,0.013,0.21,-0.029,-0.0016,-0.0057,-0.0015,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00019,0.00049,0.00049,0.00028,2.1,2.1,0.012,9.9,9.9,0.048,9.3e-05,9.3e-05,0.00022,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 -10390000,0.98,-0.0055,-0.013,0.19,0.007,0.0051,-0.0025,0.00075,0.00014,-0.028,-0.0016,-0.0057,-0.0013,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00051,0.00051,0.00028,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-05,9.3e-05,0.0002,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10490000,0.98,-0.0054,-0.012,0.19,0.0083,0.0074,0.007,0.0015,0.00073,-0.023,-0.0016,-0.0057,-0.0015,-1.2e-06,8.4e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00027,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-05,9.3e-05,0.00019,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10590000,0.98,-0.0053,-0.012,0.19,-0.0013,0.0053,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-0.0012,0.00032,5.4e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00026,0.13,0.13,0.27,0.13,0.13,0.055,9.3e-05,9.3e-05,0.00017,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10690000,0.98,-0.0053,-0.012,0.19,-0.00024,0.0064,0.016,-0.0013,-0.0049,-0.017,-0.0016,-0.0057,-0.0013,0.00032,6.1e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00055,0.00055,0.00026,0.14,0.14,0.26,0.14,0.14,0.065,9.3e-05,9.3e-05,0.00016,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10790000,0.98,-0.0054,-0.012,0.19,0.0016,0.0029,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-0.0012,0.00052,0.00047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00054,0.00054,0.00025,0.1,0.1,0.17,0.091,0.091,0.062,9e-05,9e-05,0.00015,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10890000,0.98,-0.0053,-0.013,0.19,0.0016,0.0063,0.01,-0.00062,-0.0043,-0.018,-0.0016,-0.0057,-0.00088,0.00052,0.00047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00056,0.00056,0.00025,0.12,0.12,0.16,0.098,0.098,0.068,9e-05,9e-05,0.00014,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10990000,0.98,-0.0054,-0.013,0.19,0.0011,0.012,0.016,-0.00046,-0.003,-0.011,-0.0016,-0.0057,-0.00091,0.00066,0.00071,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00053,0.00053,0.00024,0.092,0.092,0.12,0.073,0.073,0.065,8.6e-05,8.6e-05,0.00014,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11090000,0.98,-0.0055,-0.013,0.19,0.0021,0.017,0.02,-0.00034,-0.0016,-0.0074,-0.0016,-0.0057,-0.0011,0.00066,0.00071,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00054,0.00054,0.00024,0.11,0.11,0.11,0.08,0.08,0.069,8.6e-05,8.6e-05,0.00013,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11190000,0.98,-0.0058,-0.013,0.19,0.0037,0.017,0.026,0.001,-0.0018,-0.00035,-0.0015,-0.0057,-0.0012,0.00063,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00049,0.00049,0.00023,0.092,0.092,0.083,0.063,0.063,0.066,8e-05,8e-05,0.00012,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11290000,0.98,-0.0058,-0.013,0.19,0.0039,0.018,0.026,0.0014,2.5e-05,-0.00012,-0.0015,-0.0057,-0.0012,0.00064,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00051,0.00051,0.00023,0.11,0.11,0.077,0.07,0.07,0.069,8e-05,8e-05,0.00011,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11390000,0.98,-0.0059,-0.013,0.19,0.0023,0.016,0.016,0.00086,-0.00079,-0.0086,-0.0014,-0.0058,-0.0011,0.0012,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00044,0.00044,0.00023,0.093,0.093,0.062,0.057,0.057,0.066,7.4e-05,7.4e-05,0.00011,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11490000,0.98,-0.0058,-0.013,0.19,0.0013,0.017,0.02,0.00098,0.00085,-0.0025,-0.0014,-0.0058,-0.001,0.0012,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00046,0.00046,0.00022,0.11,0.11,0.057,0.065,0.065,0.067,7.4e-05,7.4e-05,0.0001,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11590000,0.98,-0.0062,-0.012,0.19,0.0032,0.013,0.018,0.00082,-0.00023,-0.0036,-0.0014,-0.0058,-0.00097,0.0015,0.003,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00039,0.00039,0.00022,0.092,0.092,0.048,0.054,0.054,0.065,6.7e-05,6.7e-05,9.5e-05,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11690000,0.98,-0.0061,-0.012,0.19,0.0036,0.017,0.018,0.0012,0.0013,-0.0049,-0.0014,-0.0058,-0.00087,0.0015,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0004,0.0004,0.00021,0.11,0.11,0.044,0.062,0.062,0.066,6.7e-05,6.7e-05,9e-05,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11790000,0.98,-0.0065,-0.012,0.19,0.0023,0.011,0.019,0.00068,-0.0016,-0.002,-0.0013,-0.0059,-0.00063,0.0021,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00034,0.00034,0.00021,0.09,0.09,0.037,0.052,0.052,0.063,6.2e-05,6.2e-05,8.5e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -11890000,0.98,-0.0066,-0.012,0.19,0.005,0.013,0.017,0.001,-0.00042,-0.0013,-0.0013,-0.0059,-0.00063,0.0021,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00035,0.00035,0.00021,0.11,0.11,0.034,0.06,0.06,0.063,6.2e-05,6.2e-05,8e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -11990000,0.98,-0.0068,-0.012,0.19,0.0079,0.013,0.015,0.0021,-0.0016,-0.0049,-0.0012,-0.0059,-0.00054,0.0021,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0003,0.0003,0.0002,0.086,0.086,0.03,0.051,0.051,0.061,5.7e-05,5.7e-05,7.6e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12090000,0.98,-0.0067,-0.012,0.19,0.0095,0.013,0.018,0.003,-0.00037,0.0011,-0.0012,-0.0059,-0.00051,0.002,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00031,0.00031,0.0002,0.1,0.1,0.027,0.059,0.059,0.06,5.7e-05,5.7e-05,7.2e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12190000,0.98,-0.0066,-0.012,0.19,0.0077,0.012,0.017,0.0018,0.00055,0.0029,-0.0012,-0.0059,-0.00054,0.0023,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00027,0.00027,0.0002,0.081,0.081,0.024,0.05,0.05,0.058,5.3e-05,5.3e-05,6.9e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12290000,0.98,-0.0067,-0.012,0.19,0.0054,0.011,0.016,0.0025,0.0017,0.0039,-0.0012,-0.0059,-0.00056,0.0023,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00028,0.00028,0.00019,0.096,0.096,0.022,0.059,0.059,0.058,5.3e-05,5.3e-05,6.6e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12390000,0.98,-0.0068,-0.012,0.19,0.004,0.0078,0.014,0.0017,0.00065,-0.0021,-0.0012,-0.0059,-0.00053,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00025,0.00025,0.00019,0.076,0.076,0.02,0.05,0.05,0.056,4.9e-05,4.9e-05,6.2e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -12490000,0.98,-0.0068,-0.012,0.19,0.004,0.0089,0.018,0.0021,0.0015,-6.6e-05,-0.0012,-0.0059,-0.00051,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00026,0.00026,0.00019,0.089,0.089,0.018,0.058,0.058,0.055,4.9e-05,4.9e-05,5.9e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -12590000,0.98,-0.007,-0.012,0.19,0.0078,0.0022,0.02,0.0033,-0.0012,0.0017,-0.0012,-0.0059,-0.00049,0.0026,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00023,0.00023,0.00018,0.071,0.071,0.017,0.049,0.049,0.054,4.7e-05,4.7e-05,5.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -12690000,0.98,-0.007,-0.012,0.19,0.0083,0.0001,0.019,0.004,-0.0011,0.0033,-0.0012,-0.0059,-0.00046,0.0026,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00024,0.00024,0.00018,0.083,0.083,0.016,0.058,0.058,0.053,4.7e-05,4.7e-05,5.4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -12790000,0.98,-0.0072,-0.012,0.19,0.0099,-0.0034,0.021,0.0041,-0.0042,0.0054,-0.0011,-0.0059,-0.00026,0.0027,0.0047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00022,0.00022,0.00018,0.067,0.067,0.014,0.049,0.049,0.052,4.4e-05,4.4e-05,5.2e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -12890000,0.98,-0.0072,-0.012,0.19,0.01,-0.0042,0.022,0.0051,-0.0046,0.0085,-0.0011,-0.0059,-0.00013,0.0027,0.0047,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00023,0.00023,0.00018,0.077,0.077,0.013,0.058,0.058,0.051,4.4e-05,4.4e-05,4.9e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -12990000,0.98,-0.0072,-0.012,0.19,0.008,-0.0023,0.022,0.0036,-0.0034,0.0096,-0.0011,-0.006,-1.1e-05,0.0028,0.0046,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.063,0.063,0.012,0.049,0.049,0.05,4.2e-05,4.2e-05,4.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13090000,0.98,-0.0072,-0.012,0.19,0.0089,-0.0022,0.02,0.0044,-0.0036,0.0085,-0.0011,-0.006,0.00013,0.0028,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00022,0.00022,0.00017,0.072,0.072,0.012,0.057,0.057,0.049,4.2e-05,4.2e-05,4.5e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13190000,0.98,-0.0072,-0.012,0.19,0.0039,-0.0039,0.019,0.00095,-0.0044,0.0091,-0.0011,-0.006,0.00022,0.0029,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.059,0.059,0.011,0.049,0.049,0.047,4e-05,4e-05,4.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0048,0.016,0.0013,-0.0048,0.0085,-0.0011,-0.006,0.00024,0.0029,0.0044,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00017,0.067,0.067,0.01,0.057,0.057,0.047,4e-05,4e-05,4.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13390000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0029,0.016,0.00084,-0.0036,0.0091,-0.0011,-0.006,0.0002,0.003,0.0044,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.056,0.056,0.0097,0.049,0.049,0.046,3.8e-05,3.8e-05,4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13490000,0.98,-0.0072,-0.012,0.19,0.0031,-0.0012,0.015,0.0011,-0.0038,0.0053,-0.0011,-0.006,0.00024,0.0031,0.0043,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00021,0.00021,0.00016,0.063,0.063,0.0093,0.056,0.056,0.045,3.8e-05,3.8e-05,3.8e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0015,0.017,0.004,-0.0031,0.0038,-0.0011,-0.006,0.00022,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.053,0.053,0.0088,0.048,0.048,0.044,3.6e-05,3.6e-05,3.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13690000,0.98,-0.0071,-0.012,0.19,0.0076,-0.0029,0.017,0.0047,-0.0033,0.0064,-0.0011,-0.006,0.00029,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.06,0.06,0.0085,0.056,0.056,0.044,3.6e-05,3.6e-05,3.5e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13790000,0.98,-0.0071,-0.012,0.19,0.015,0.0012,0.017,0.0083,-0.00086,0.0059,-0.0011,-0.0059,0.00026,0.0036,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00016,0.05,0.05,0.0082,0.048,0.048,0.043,3.5e-05,3.5e-05,3.4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13890000,0.98,-0.007,-0.012,0.19,0.016,0.0019,0.018,0.0098,-0.00069,0.0081,-0.0011,-0.0059,0.00034,0.0036,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.057,0.057,0.008,0.056,0.056,0.042,3.5e-05,3.5e-05,3.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -13990000,0.98,-0.007,-0.012,0.19,0.015,0.002,0.017,0.0073,-0.0022,0.007,-0.0011,-0.006,0.00042,0.0034,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00015,0.048,0.048,0.0077,0.048,0.048,0.041,3.3e-05,3.3e-05,3.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0024,0.018,0.0088,-0.0023,0.0034,-0.0011,-0.0059,0.00026,0.0035,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.055,0.055,0.0076,0.055,0.055,0.041,3.3e-05,3.3e-05,3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14190000,0.98,-0.007,-0.012,0.19,0.01,-0.0012,0.018,0.008,-0.0017,0.0036,-0.0011,-0.006,0.00019,0.0036,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00015,0.046,0.046,0.0074,0.048,0.048,0.04,3.1e-05,3.1e-05,2.9e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0012,0.016,0.009,-0.0018,0.0079,-0.0011,-0.006,0.0002,0.0036,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00015,0.052,0.052,0.0073,0.055,0.055,0.04,3.1e-05,3.1e-05,2.8e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0042,0.017,0.0084,-0.003,0.012,-0.0011,-0.006,0.00025,0.0035,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.045,0.045,0.0071,0.048,0.048,0.039,3e-05,3e-05,2.7e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0039,0.021,0.0095,-0.0034,0.015,-0.0011,-0.006,0.00018,0.0034,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0002,0.0002,0.00014,0.051,0.051,0.0071,0.055,0.055,0.038,3e-05,3e-05,2.6e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14590000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0041,0.019,0.0059,-0.0041,0.011,-0.0011,-0.006,0.00017,0.0032,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.044,0.044,0.007,0.047,0.047,0.038,2.8e-05,2.8e-05,2.5e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14690000,0.98,-0.0072,-0.011,0.19,0.0073,-0.0041,0.019,0.0067,-0.0045,0.011,-0.0011,-0.006,0.0002,0.0033,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.049,0.049,0.007,0.054,0.054,0.037,2.8e-05,2.8e-05,2.4e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14790000,0.98,-0.0072,-0.011,0.19,0.009,0.0028,0.019,0.0053,0.00086,0.014,-0.0012,-0.006,0.00029,0.0033,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.042,0.042,0.0069,0.047,0.047,0.037,2.6e-05,2.6e-05,2.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14890000,0.98,-0.0071,-0.011,0.19,0.0077,0.00045,0.023,0.0061,0.001,0.014,-0.0012,-0.006,0.00035,0.0034,0.0045,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.048,0.048,0.007,0.054,0.054,0.037,2.6e-05,2.6e-05,2.3e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14990000,0.98,-0.0072,-0.011,0.19,0.0064,-0.0012,0.026,0.0048,-0.00061,0.017,-0.0012,-0.006,0.00039,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00014,0.042,0.042,0.0069,0.047,0.047,0.036,2.5e-05,2.5e-05,2.2e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15090000,0.98,-0.0072,-0.011,0.19,0.0065,-0.00011,0.03,0.0054,-0.00072,0.019,-0.0012,-0.006,0.00038,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.047,0.047,0.007,0.054,0.054,0.036,2.5e-05,2.5e-05,2.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15190000,0.98,-0.0073,-0.011,0.19,0.0046,-0.0012,0.03,0.0042,-0.00067,0.021,-0.0012,-0.0061,0.00036,0.0032,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.041,0.041,0.007,0.047,0.047,0.036,2.3e-05,2.3e-05,2e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15290000,0.98,-0.0074,-0.011,0.19,0.0052,-0.0023,0.03,0.0048,-0.00083,0.018,-0.0012,-0.0061,0.00042,0.0034,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.046,0.046,0.0071,0.054,0.054,0.035,2.3e-05,2.3e-05,2e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15390000,0.98,-0.0075,-0.011,0.19,0.0054,8.3e-05,0.029,0.0038,-0.00056,0.018,-0.0012,-0.0061,0.00041,0.0035,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.04,0.04,0.007,0.047,0.047,0.035,2.1e-05,2.1e-05,1.9e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15490000,0.98,-0.0075,-0.011,0.19,0.0048,-0.0024,0.029,0.0043,-0.00065,0.019,-0.0012,-0.0061,0.00041,0.0036,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00019,0.00019,0.00013,0.045,0.045,0.0072,0.053,0.053,0.035,2.1e-05,2.1e-05,1.8e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.0063,0.029,0.0063,-0.0046,0.018,-0.0011,-0.0061,0.00045,0.0039,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.04,0.04,0.0072,0.046,0.046,0.035,2e-05,2e-05,1.8e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15690000,0.98,-0.0077,-0.011,0.19,0.01,-0.0093,0.029,0.0072,-0.0054,0.019,-0.0011,-0.0061,0.00049,0.004,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00013,0.044,0.045,0.0073,0.053,0.053,0.034,2e-05,2e-05,1.7e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15790000,0.98,-0.0077,-0.011,0.19,0.0066,-0.0087,0.029,0.0055,-0.0042,0.02,-0.0011,-0.0061,0.00056,0.0038,0.0031,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00017,0.00012,0.039,0.039,0.0073,0.046,0.046,0.034,1.8e-05,1.8e-05,1.7e-05,0.033,0.034,0.0005,0,0,0,0,0,0,0,0 -15890000,0.98,-0.0077,-0.011,0.19,0.0055,-0.0071,0.03,0.0061,-0.005,0.02,-0.0011,-0.0061,0.00051,0.0041,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00018,0.00012,0.044,0.044,0.0074,0.053,0.053,0.034,1.8e-05,1.8e-05,1.6e-05,0.033,0.034,0.0005,0,0,0,0,0,0,0,0 -15990000,0.98,-0.0075,-0.011,0.19,0.0035,-0.0057,0.027,0.0048,-0.0038,0.019,-0.0012,-0.0061,0.0005,0.0043,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.038,0.038,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,1.6e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16090000,0.98,-0.0075,-0.011,0.19,0.0029,-0.0069,0.024,0.0051,-0.0045,0.019,-0.0012,-0.0061,0.00047,0.0044,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00018,0.00017,0.00012,0.043,0.043,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,1.5e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16190000,0.98,-0.0074,-0.011,0.19,-0.001,-0.0046,0.023,0.0028,-0.0033,0.016,-0.0012,-0.0061,0.00043,0.0045,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.038,0.038,0.0076,0.046,0.046,0.034,1.5e-05,1.5e-05,1.5e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16290000,0.98,-0.0075,-0.011,0.19,-0.0007,-0.0061,0.023,0.0026,-0.0039,0.017,-0.0012,-0.0061,0.00044,0.0045,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.043,0.043,0.0077,0.053,0.053,0.034,1.5e-05,1.5e-05,1.4e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16390000,0.98,-0.0074,-0.011,0.19,0.0017,-0.0054,0.023,0.0037,-0.0029,0.017,-0.0012,-0.0061,0.00048,0.0051,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00012,0.037,0.038,0.0077,0.046,0.046,0.034,1.4e-05,1.4e-05,1.4e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16490000,0.98,-0.0075,-0.011,0.19,0.0037,-0.007,0.026,0.0039,-0.0036,0.021,-0.0012,-0.0061,0.00047,0.005,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00017,0.00017,0.00012,0.042,0.042,0.0079,0.052,0.053,0.034,1.4e-05,1.4e-05,1.4e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16590000,0.98,-0.0075,-0.011,0.19,0.0078,-0.0071,0.029,0.0034,-0.0028,0.021,-0.0012,-0.0061,0.00046,0.0051,0.003,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00012,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,1.3e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16690000,0.98,-0.0076,-0.011,0.19,0.0092,-0.012,0.029,0.0043,-0.0037,0.022,-0.0012,-0.0061,0.00049,0.0053,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00011,0.041,0.041,0.008,0.052,0.052,0.034,1.3e-05,1.3e-05,1.3e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16790000,0.98,-0.0074,-0.011,0.19,0.01,-0.011,0.028,0.0033,-0.0027,0.022,-0.0012,-0.0061,0.0005,0.0053,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00015,0.00011,0.036,0.036,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,1.2e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16890000,0.98,-0.0074,-0.011,0.19,0.0091,-0.011,0.029,0.0043,-0.0037,0.02,-0.0012,-0.0061,0.00055,0.0056,0.0029,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00016,0.00016,0.00011,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,1.2e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16990000,0.98,-0.0074,-0.011,0.19,0.0088,-0.01,0.029,0.0041,-0.0028,0.019,-0.0012,-0.0061,0.00056,0.0062,0.003,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,1.2e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.0051,-0.004,0.018,-0.0012,-0.0061,0.00054,0.0065,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17190000,0.98,-0.0076,-0.011,0.19,0.0092,-0.018,0.03,0.0034,-0.0075,0.021,-0.0012,-0.0061,0.00049,0.0063,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.035,0.035,0.0083,0.046,0.046,0.034,9.7e-06,9.7e-06,1.1e-05,0.031,0.032,0.0005,0,0,0,0,0,0,0,0 -17290000,0.98,-0.0076,-0.011,0.19,0.01,-0.019,0.03,0.0044,-0.0093,0.021,-0.0012,-0.0061,0.00045,0.0065,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00015,0.00011,0.039,0.039,0.0084,0.052,0.052,0.034,9.7e-06,9.7e-06,1.1e-05,0.031,0.032,0.0005,0,0,0,0,0,0,0,0 -17390000,0.98,-0.0074,-0.011,0.19,0.0069,-0.018,0.029,0.0058,-0.0059,0.021,-0.0013,-0.006,0.00048,0.0073,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.00011,0.035,0.035,0.0084,0.046,0.046,0.034,8.8e-06,8.8e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17490000,0.98,-0.0075,-0.011,0.19,0.005,-0.019,0.029,0.0063,-0.0077,0.023,-0.0013,-0.006,0.00046,0.0074,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00015,0.00014,0.00011,0.039,0.039,0.0085,0.052,0.052,0.034,8.8e-06,8.8e-06,1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17590000,0.98,-0.0074,-0.011,0.19,0.0011,-0.015,0.028,0.0025,-0.0058,0.02,-0.0013,-0.0061,0.00046,0.0073,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.00011,0.034,0.034,0.0085,0.046,0.046,0.034,7.9e-06,7.9e-06,1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17690000,0.98,-0.0074,-0.011,0.19,0.00021,-0.016,0.029,0.0026,-0.0073,0.023,-0.0013,-0.0061,0.00046,0.0073,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.0001,0.038,0.038,0.0086,0.052,0.052,0.034,7.9e-06,7.9e-06,9.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17790000,0.98,-0.0074,-0.011,0.19,0.0028,-0.014,0.029,0.0036,-0.0062,0.028,-0.0014,-0.006,0.00046,0.0077,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00013,0.0001,0.033,0.033,0.0086,0.045,0.045,0.034,7.2e-06,7.2e-06,9.5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17890000,0.98,-0.0073,-0.011,0.19,0.0049,-0.016,0.029,0.004,-0.0077,0.032,-0.0014,-0.006,0.00047,0.0076,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00014,0.00014,0.0001,0.037,0.037,0.0086,0.052,0.052,0.035,7.2e-06,7.2e-06,9.3e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17990000,0.98,-0.0071,-0.011,0.19,0.0043,-0.0093,0.029,0.0032,-0.002,0.033,-0.0014,-0.006,0.00047,0.008,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.033,0.033,0.0086,0.045,0.045,0.034,6.5e-06,6.5e-06,9.1e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18090000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0098,0.028,0.0036,-0.003,0.031,-0.0014,-0.006,0.00046,0.0083,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.036,0.036,0.0087,0.051,0.051,0.035,6.5e-06,6.5e-06,8.9e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18190000,0.98,-0.0072,-0.011,0.19,0.0039,-0.0088,0.028,0.0042,-0.0022,0.029,-0.0014,-0.006,0.0005,0.0088,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.032,0.032,0.0086,0.045,0.045,0.035,5.9e-06,5.9e-06,8.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18290000,0.98,-0.0072,-0.011,0.19,0.0048,-0.0093,0.027,0.0046,-0.0031,0.027,-0.0014,-0.006,0.0005,0.0091,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,0.0001,0.035,0.035,0.0087,0.051,0.051,0.035,5.9e-06,5.9e-06,8.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18390000,0.98,-0.0071,-0.011,0.19,0.0056,-0.008,0.027,0.0062,-0.0023,0.026,-0.0014,-0.006,0.00048,0.0096,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.9e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.3e-06,5.3e-06,8.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18490000,0.98,-0.0072,-0.011,0.19,0.0084,-0.008,0.026,0.007,-0.0032,0.028,-0.0014,-0.006,0.0005,0.0097,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00013,0.00013,9.9e-05,0.034,0.034,0.0087,0.051,0.051,0.035,5.3e-06,5.3e-06,8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18590000,0.98,-0.007,-0.011,0.19,0.0068,-0.0074,0.026,0.0056,-0.0024,0.031,-0.0015,-0.006,0.00046,0.0096,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.8e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.8e-06,4.8e-06,7.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18690000,0.98,-0.007,-0.011,0.19,0.0069,-0.0063,0.024,0.0063,-0.0031,0.029,-0.0015,-0.006,0.00048,0.0098,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.7e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.8e-06,4.8e-06,7.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18790000,0.98,-0.007,-0.011,0.19,0.0058,-0.006,0.024,0.0063,-0.0025,0.027,-0.0015,-0.006,0.00047,0.01,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.6e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,7.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18890000,0.98,-0.0069,-0.011,0.19,0.0045,-0.0056,0.021,0.0068,-0.0032,0.023,-0.0015,-0.006,0.00045,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.6e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,7.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18990000,0.98,-0.0069,-0.011,0.19,0.0028,-0.0057,0.022,0.0056,-0.0025,0.026,-0.0015,-0.006,0.00045,0.01,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00011,9.5e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,7.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19090000,0.98,-0.007,-0.011,0.19,0.00087,-0.0062,0.023,0.0059,-0.0031,0.022,-0.0015,-0.006,0.00046,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,9.4e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19190000,0.98,-0.0069,-0.011,0.19,-0.00064,-0.0059,0.022,0.0049,-0.0025,0.022,-0.0015,-0.006,0.00042,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.4e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.6e-06,3.6e-06,6.8e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19290000,0.98,-0.0068,-0.011,0.19,-0.0015,-0.0057,0.023,0.0048,-0.0031,0.021,-0.0015,-0.006,0.00041,0.011,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.3e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.6e-06,3.6e-06,6.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19390000,0.98,-0.0069,-0.011,0.19,-0.002,-0.0022,0.024,0.0041,-0.0012,0.019,-0.0015,-0.006,0.00039,0.011,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.2e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,6.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19490000,0.98,-0.0069,-0.011,0.19,-0.0028,-0.0022,0.023,0.0039,-0.0014,0.019,-0.0015,-0.006,0.00036,0.011,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.2e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,6.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19590000,0.98,-0.0069,-0.011,0.19,-0.0039,-0.0051,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,0.00034,0.012,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9.1e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,6.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19690000,0.98,-0.0069,-0.011,0.19,-0.0055,-0.0037,0.023,0.004,-0.0028,0.019,-0.0015,-0.006,0.00036,0.012,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,9e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,6.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19790000,0.98,-0.007,-0.011,0.19,-0.0056,-0.0022,0.022,0.0064,-0.0023,0.014,-0.0015,-0.006,0.00033,0.012,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,9e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19890000,0.98,-0.007,-0.011,0.19,-0.0056,-0.002,0.022,0.0058,-0.0025,0.013,-0.0015,-0.006,0.00032,0.013,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,8.9e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,5.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -19990000,0.98,-0.0071,-0.011,0.19,-0.0053,-0.0019,0.019,0.0062,-0.00091,0.0097,-0.0015,-0.0059,0.00032,0.013,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.8e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,5.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20090000,0.98,-0.0071,-0.011,0.19,-0.0048,-0.0042,0.019,0.0056,-0.0012,0.013,-0.0015,-0.0059,0.00031,0.013,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,8.8e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,5.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20190000,0.98,-0.0071,-0.011,0.19,-0.0038,-0.0016,0.02,0.0066,-0.0009,0.013,-0.0015,-0.0059,0.00029,0.013,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.7e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,5.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20290000,0.98,-0.007,-0.011,0.19,-0.007,-0.0027,0.02,0.0061,-0.0011,0.013,-0.0015,-0.0059,0.00028,0.013,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.7e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,5.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20390000,0.98,-0.007,-0.011,0.19,-0.0077,-0.0015,0.021,0.0069,-0.00077,0.014,-0.0015,-0.0059,0.00029,0.014,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,8.6e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,5.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.006,-0.00095,0.012,-0.0015,-0.0059,0.00028,0.014,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,8.6e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,5.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.007,-0.00079,0.011,-0.0015,-0.0059,0.00031,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.9e-05,9.8e-05,8.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0022,0.021,0.0058,-0.001,0.011,-0.0015,-0.0059,0.00028,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,8.5e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.0004,0.0055,0.0049,-0.00081,0.0097,-0.0015,-0.0059,0.00029,0.014,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.6e-05,8.4e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,4.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20890000,0.98,0.0028,-0.0073,0.19,-0.021,0.012,-0.11,0.003,-0.00013,0.0034,-0.0015,-0.0059,0.00029,0.015,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.7e-05,8.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,4.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0023,0.00052,-0.011,-0.0015,-0.0059,0.00028,0.015,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.6e-05,9.5e-05,8.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,4.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21090000,0.98,0.0045,-0.0042,0.19,-0.045,0.046,-0.37,-0.0016,0.0044,-0.042,-0.0015,-0.0059,0.00028,0.015,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.7e-05,9.5e-05,8.2e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,4.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0012,0.0035,-0.078,-0.0014,-0.0059,0.00028,0.015,0.0016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.3e-05,8.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.5e-06,1.5e-06,4.5e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.98,-0.0005,-0.0072,0.19,-0.049,0.054,-0.63,-0.0061,0.0087,-0.14,-0.0014,-0.0059,0.00025,0.015,0.0016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.4e-05,8.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.5e-06,1.5e-06,4.4e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,0.00025,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.1e-05,8.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,4.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0092,0.016,-0.29,-0.0014,-0.0059,0.00026,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.2e-05,8e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,4.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.0079,0.016,-0.38,-0.0014,-0.0059,0.00027,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,9e-05,8e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,4.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,0.00029,0.015,0.0009,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,9e-05,7.9e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,4.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0037,0.018,-0.61,-0.0014,-0.0058,0.00031,0.016,0.00068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.8e-05,7.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0056,0.021,-0.75,-0.0014,-0.0058,0.00029,0.016,0.00056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.8e-05,7.8e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,3.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00032,0.017,-0.89,-0.0014,-0.0058,0.0003,0.015,0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,7.8e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,3.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0016,0.019,-1,-0.0014,-0.0058,0.00032,0.016,0.00066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,7.8e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-06,1.1e-06,3.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.0061,0.013,-1.2,-0.0014,-0.0058,0.00033,0.016,0.00068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.5e-05,8.4e-05,7.7e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22290000,0.98,-0.0069,-0.01,0.19,0.0017,0.0078,-1.4,0.006,0.014,-1.3,-0.0014,-0.0058,0.00032,0.016,0.00058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.6e-05,8.4e-05,7.7e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,3.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22390000,0.98,-0.0072,-0.01,0.19,0.0067,-0.0018,-1.4,0.013,0.0042,-1.5,-0.0014,-0.0058,0.0003,0.016,0.0002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,7.6e-05,0.021,0.021,0.0081,0.042,0.043,0.036,1e-06,1e-06,3.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22490000,0.98,-0.0074,-0.011,0.19,0.011,-0.0078,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,0.00028,0.016,0.00013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.4e-05,8.3e-05,7.6e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,3.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,0.0003,0.016,-4.2e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,8.1e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,3.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,0.00029,0.016,-0.00012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.3e-05,8.2e-05,7.5e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-07,9.4e-07,3.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,0.00027,0.016,-0.00023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,8e-05,7.5e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,3.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,0.00029,0.016,-0.00031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,8e-05,7.4e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,3.3e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,0.00031,0.016,-0.00045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,7.4e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,3.2e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,0.00031,0.017,-0.00048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.9e-05,7.3e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,3.2e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,0.00029,0.017,-0.00063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,7.3e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-07,7.9e-07,3.1e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,0.0003,0.017,-0.00068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,7.3e-05,0.019,0.02,0.0081,0.046,0.046,0.036,7.9e-07,7.9e-07,3.1e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,0.00028,0.017,-0.00041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.2e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-07,7.5e-07,3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -23490000,0.98,-0.0079,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,0.00029,0.017,-0.00046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,7.2e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.5e-07,7.5e-07,3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,0.0003,0.017,-0.00058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.1e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,2.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0059,0.00031,0.017,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,7.1e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,2.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,0.00032,0.017,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7.1e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.8e-07,6.8e-07,2.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -23890000,0.98,-0.014,-0.021,0.18,0.053,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,0.00032,0.017,-0.00061,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,2.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.13,-0.089,-3.6,-0.0014,-0.0058,0.00032,0.018,-0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,2.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24090000,0.98,-0.016,-0.023,0.18,0.061,-0.066,0.09,0.13,-0.096,-3.6,-0.0014,-0.0058,0.00031,0.018,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,7e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,2.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24190000,0.98,-0.013,-0.019,0.18,0.072,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,2.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-07,6.3e-07,2.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00034,0.019,-0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.9e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,2.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00036,0.019,-0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,2.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00036,0.019,-0.0034,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,2.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24690000,0.98,-0.011,-0.014,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,0.00035,0.019,-0.0034,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.8e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,2.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.004,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,2.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.004,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,2.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.0046,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.7e-05,7.6e-05,6.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,2.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00036,0.019,-0.0047,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.6e-05,6.6e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,2.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00035,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.6e-05,6.6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,2.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0052,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.6e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,2.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00033,0.018,-0.0058,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-07,5.1e-07,2.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0059,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-07,5.1e-07,2.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25590000,0.98,-0.011,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,0.00031,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,2.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00031,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.5e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,0.0003,0.018,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-07,4.8e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25890000,0.98,-0.011,-0.011,0.19,-0.0036,-0.029,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-07,4.8e-07,2.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -25990000,0.98,-0.011,-0.011,0.19,-0.012,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.4e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.022,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0073,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.8e-05,7.7e-05,6.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26290000,0.98,-0.01,-0.012,0.18,-0.025,-0.014,0.00052,0.15,-0.083,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0073,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26390000,0.98,-0.0098,-0.012,0.18,-0.031,-0.0065,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0076,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.7e-05,6.3e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0034,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00025,0.019,-0.0076,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0046,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,0.00023,0.019,-0.0078,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0097,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0078,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-07,4.3e-07,1.9e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.9e-05,7.8e-05,6.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.2e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26890000,0.98,-0.008,-0.011,0.18,-0.051,0.016,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-07,4.2e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.8e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.035,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27290000,0.98,-0.0075,-0.013,0.18,-0.073,0.041,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-07,4e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27390000,0.98,-0.0089,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,0.00017,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,6e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.03,-3.5,-0.0016,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,6e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,0.00015,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,6e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.7e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27690000,0.98,-0.0089,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.049,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27890000,0.98,-0.0072,-0.012,0.18,-0.078,0.057,0.79,0.018,-0.012,-3.2,-0.0016,-0.0058,0.00014,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,0.00014,0.02,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0048,-3,-0.0016,-0.0058,0.00015,0.02,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.6e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0022,-0.0044,-3,-0.0016,-0.0058,0.00014,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0014,-2.9,-0.0016,-0.0058,0.00015,0.02,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0043,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28590000,0.98,-0.0072,-0.014,0.18,-0.083,0.06,0.79,-0.027,0.0084,-2.7,-0.0015,-0.0058,0.00015,0.02,-0.0078,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.7e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-07,3.5e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28690000,0.98,-0.007,-0.013,0.18,-0.083,0.061,0.79,-0.036,0.014,-2.6,-0.0015,-0.0058,0.00014,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.5e-07,1.5e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28890000,0.98,-0.0062,-0.012,0.18,-0.083,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.7e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.045,0.022,-2.4,-0.0015,-0.0058,0.00015,0.02,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,0.00015,0.02,-0.0082,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29290000,0.98,-0.006,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.033,-2.2,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,0.00016,0.02,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,0.00017,0.02,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29690000,0.98,-0.0064,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29790000,0.98,-0.0063,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.043,-1.8,-0.0014,-0.0058,0.00019,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29890000,0.98,-0.0057,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,0.0002,0.02,-0.0094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,0.0002,0.021,-0.0098,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30090000,0.98,-0.006,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,0.00019,0.021,-0.0099,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.4e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,0.00017,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30290000,0.98,-0.006,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,0.00018,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,5.4e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30390000,0.98,-0.006,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30490000,0.98,-0.006,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,0.0002,0.022,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30690000,0.98,-0.0067,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,0.0002,0.022,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.014,0.008,0.041,0.041,0.035,3e-07,3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30790000,0.98,-0.0064,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,0.00019,0.023,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.3e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31090000,0.98,-0.0061,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,0.00019,0.023,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31190000,0.98,-0.0063,-0.013,0.19,-0.031,0.021,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,0.00021,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31390000,0.98,-0.0063,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31590000,0.98,-0.0059,-0.014,0.18,-0.018,0.0068,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,0.00021,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31690000,0.98,-0.0059,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,0.00022,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31790000,0.98,-0.0061,-0.015,0.18,-0.011,0.0032,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,0.00022,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00086,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00023,0.024,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31990000,0.98,-0.0061,-0.015,0.18,-0.00013,0.00021,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,0.00022,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32090000,0.98,-0.0065,-0.014,0.18,-0.00067,-0.0032,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00022,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32190000,0.98,-0.0067,-0.015,0.18,0.0046,-0.0064,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00022,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5.1e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0091,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00023,0.025,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32390000,0.98,-0.0067,-0.015,0.18,0.012,-0.01,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.8e-05,5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-07,2.7e-07,9.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8e-05,7.9e-05,5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,9.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.074,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.7e-05,5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-07,2.7e-07,9.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,0.00022,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.9e-05,7.8e-05,5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-07,2.7e-07,9.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0057,0.00023,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.6e-05,7.5e-05,5e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32890000,0.98,-0.0091,-0.013,0.18,0.033,-0.083,-0.13,0.038,0.0021,-0.011,-0.0014,-0.0057,0.00023,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.6e-05,7.5e-05,4.9e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.001,-0.024,-0.0014,-0.0056,0.00024,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.2e-05,7.1e-05,4.9e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,9.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0091,-0.031,-0.0014,-0.0056,0.00024,0.026,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.2e-05,7.1e-05,4.9e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,9.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6.6e-05,6.6e-05,4.9e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-07,2.6e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6.7e-05,6.6e-05,4.9e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-07,2.6e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6e-05,5.9e-05,4.9e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,6e-05,5.9e-05,4.9e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-07,2.6e-07,9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,0.00025,0.025,-0.018,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,5.3e-05,5.2e-05,4.8e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,8.9e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33690000,0.98,-0.0077,-0.013,0.18,0.00081,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00025,0.025,-0.018,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,5.3e-05,5.2e-05,4.8e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,8.8e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.048,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,0.00024,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.6e-05,4.6e-05,4.8e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,8.7e-07,0.025,0.026,0.0005,0,0,0,0,0,0,0,0 -33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.046,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,0.00025,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.7e-05,4.6e-05,4.8e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,8.7e-07,0.025,0.026,0.0005,0,0,0,0,0,0,0,0 -33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.1e-05,4.1e-05,4.8e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,8.6e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 -34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,4.1e-05,4.1e-05,4.8e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,8.5e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 -34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.021,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.7e-05,3.6e-05,4.8e-05,0.047,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,8.5e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 -34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.7e-05,3.6e-05,4.7e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,8.4e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 -34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.072,-0.01,-0.11,-0.0014,-0.0056,0.00024,0.018,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.3e-05,3.3e-05,4.7e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,8.3e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0096,-0.09,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00024,0.017,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.3e-05,3.3e-05,4.7e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,8.3e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34590000,0.98,-0.0068,-0.013,0.18,-0.014,-0.0053,0.71,0.073,-0.0089,-0.081,-0.0014,-0.0056,0.00024,0.016,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.1e-05,3.1e-05,4.7e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-07,2.6e-07,8.2e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0032,1.7,0.071,-0.0093,0.038,-0.0014,-0.0056,0.00023,0.016,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,3.1e-05,3.1e-05,4.7e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-07,2.6e-07,8.1e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0014,2.7,0.072,-0.0069,0.21,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00017,2.9e-05,2.9e-05,4.7e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-07,2.6e-07,8.1e-07,0.02,0.02,0.0005,0,0,0,0,0,0,0,0 -34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0038,3.6,0.07,-0.0065,0.5,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00017,2.9e-05,2.9e-05,4.7e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-07,2.6e-07,8e-07,0.02,0.02,0.0005,0,0,0,0,0,0,0,0 +10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.8e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,5.8e-07,0.0025,0.0025,0.00025,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,6.2e-07,0.0026,0.0026,0.00032,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2e-11,0,0,-6.8e-08,0,0,0,0,0,0,0,0,6.7e-07,0.0027,0.0027,0.00044,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +290000,1,-0.012,-0.011,0.00045,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.9e-09,-5.9e-09,-2.3e-10,0,0,-2.9e-06,0,0,0,0,0,0,0,0,7.4e-07,0.0029,0.0029,0.00021,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +390000,1,-0.012,-0.011,0.0005,-0.0025,-0.006,-0.063,-0.00056,-0.00072,-0.013,-7.2e-09,-5.8e-09,-1.9e-10,0,0,8.8e-06,0,0,0,0,0,0,0,0,8.2e-07,0.0031,0.0031,0.0003,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0067,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +490000,1,-0.012,-0.012,0.00056,-0.0007,-0.0063,-0.069,-0.00015,-0.00047,-0.011,-1.2e-06,7.4e-07,-7.3e-10,0,0,1.6e-05,0,0,0,0,0,0,0,0,9.2e-07,0.0034,0.0034,0.00018,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +590000,1,-0.012,-0.012,0.00058,-0.002,-0.009,-0.12,-0.00028,-0.0013,-0.029,-1.3e-06,7.7e-07,-6.4e-10,0,0,6.4e-05,0,0,0,0,0,0,0,0,1e-06,0.0037,0.0037,0.00026,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0042,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +690000,1,-0.012,-0.012,0.00062,5.3e-05,-0.0089,-0.05,-8e-05,-0.00079,-0.0088,-5.6e-06,1.6e-06,-3e-08,0,0,-9.5e-05,0,0,0,0,0,0,0,0,1.2e-06,0.004,0.004,0.00016,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0025,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +790000,1,-0.012,-0.012,0.00062,0.0022,-0.011,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,-2.9e-08,0,0,-0.00013,0,0,0,0,0,0,0,0,1.3e-06,0.0044,0.0044,0.00022,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0025,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +890000,1,-0.012,-0.013,0.00063,0.0031,-0.0085,-0.093,0.00015,-0.0011,-0.031,-2.2e-05,1.1e-06,5.8e-07,0,0,-3.3e-05,0,0,0,0,0,0,0,0,1.5e-06,0.0048,0.0048,0.00014,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.0016,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +990000,1,-0.012,-0.013,0.0006,0.006,-0.0099,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.1e-06,5.9e-07,0,0,1.3e-05,0,0,0,0,0,0,0,0,1.7e-06,0.0053,0.0053,0.00018,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.0016,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1090000,1,-0.012,-0.013,0.00056,0.011,-0.013,-0.13,0.00077,-0.0015,-0.062,-6.1e-05,-1.5e-05,2.9e-06,0,0,4.5e-05,0,0,0,0,0,0,0,0,1.8e-06,0.0057,0.0057,0.00012,0.92,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.001,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1190000,1,-0.012,-0.013,0.0005,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,2.7e-06,0,0,-0.00048,0,0,0,0,0,0,0,0,2.1e-06,0.0063,0.0063,0.00016,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.001,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1290000,1,-0.012,-0.014,0.00045,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00017,-9.6e-05,1e-05,0,0,-0.00075,0,0,0,0,0,0,0,0,2.2e-06,0.0064,0.0064,0.00011,0.88,0.88,0.41,0.15,0.15,0.18,0.0095,0.0095,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1390000,1,-0.012,-0.014,0.00041,0.026,-0.023,-0.097,0.0043,-0.0045,-0.038,-0.00016,-9.1e-05,9.8e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,2.4e-06,0.0071,0.0071,0.00014,1.1,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00068,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1490000,1,-0.012,-0.014,0.0004,0.024,-0.021,-0.12,0.0034,-0.0033,-0.053,-0.00039,-0.00033,2.5e-05,0,0,-0.0012,0,0,0,0,0,0,0,0,2.3e-06,0.0067,0.0067,0.0001,0.95,0.95,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00048,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1590000,1,-0.012,-0.014,0.00042,0.031,-0.025,-0.13,0.0061,-0.0056,-0.063,-0.00039,-0.00033,2.5e-05,0,0,-0.0014,0,0,0,0,0,0,0,0,2.6e-06,0.0073,0.0073,0.00012,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00048,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1690000,1,-0.012,-0.014,0.00045,0.028,-0.02,-0.13,0.0044,-0.0037,-0.068,-0.00074,-0.00073,4.7e-05,0,0,-0.0018,0,0,0,0,0,0,0,0,2.3e-06,0.0063,0.0064,9.2e-05,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00035,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +1790000,1,-0.012,-0.014,0.00041,0.036,-0.024,-0.13,0.0076,-0.006,-0.067,-0.00073,-0.00073,4.7e-05,0,0,-0.0028,0,0,0,0,0,0,0,0,2.6e-06,0.007,0.007,0.00011,1.3,1.3,0.16,0.2,0.2,0.12,0.0078,0.0078,0.00035,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +1890000,1,-0.012,-0.014,0.0004,0.043,-0.026,-0.14,0.012,-0.0085,-0.075,-0.00073,-0.00072,4.7e-05,0,0,-0.0032,0,0,0,0,0,0,0,0,2.9e-06,0.0076,0.0076,0.00013,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00035,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +1990000,1,-0.011,-0.014,0.00039,0.035,-0.018,-0.14,0.0082,-0.0055,-0.074,-0.0011,-0.0013,6.9e-05,0,0,-0.0046,0,0,0,0,0,0,0,0,2.3e-06,0.006,0.006,9.6e-05,1.3,1.3,0.13,0.2,0.2,0.11,0.0066,0.0066,0.00026,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +2090000,1,-0.011,-0.014,0.00041,0.042,-0.021,-0.14,0.012,-0.0075,-0.071,-0.0011,-0.0012,6.9e-05,0,0,-0.0065,0,0,0,0,0,0,0,0,2.6e-06,0.0066,0.0066,0.00011,1.7,1.7,0.12,0.31,0.31,0.11,0.0066,0.0066,0.00026,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +2190000,1,-0.011,-0.014,0.00034,0.033,-0.014,-0.14,0.0081,-0.0044,-0.077,-0.0015,-0.0018,8.7e-05,0,0,-0.0075,0,0,0,0,0,0,0,0,2e-06,0.005,0.005,8.7e-05,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,0.0002,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2290000,1,-0.011,-0.014,0.00033,0.038,-0.015,-0.14,0.012,-0.0059,-0.075,-0.0014,-0.0018,8.6e-05,0,0,-0.0098,0,0,0,0,0,0,0,0,2.2e-06,0.0054,0.0054,9.9e-05,1.5,1.5,0.11,0.29,0.29,0.1,0.0055,0.0055,0.0002,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2390000,1,-0.011,-0.013,0.00033,0.029,-0.01,-0.14,0.0075,-0.0034,-0.072,-0.0017,-0.0023,9.8e-05,0,0,-0.012,0,0,0,0,0,0,0,0,1.6e-06,0.004,0.004,7.9e-05,1,1,0.1,0.19,0.19,0.098,0.0045,0.0045,0.00015,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +2490000,1,-0.011,-0.014,0.0004,0.033,-0.0092,-0.14,0.011,-0.0044,-0.079,-0.0017,-0.0023,9.8e-05,0,0,-0.013,0,0,0,0,0,0,0,0,1.7e-06,0.0044,0.0044,8.9e-05,1.3,1.3,0.1,0.28,0.28,0.097,0.0045,0.0045,0.00015,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +2590000,1,-0.01,-0.013,0.00029,0.023,-0.0062,-0.15,0.0066,-0.0024,-0.085,-0.0019,-0.0027,0.00011,0,0,-0.015,0,0,0,0,0,0,0,0,1.3e-06,0.0032,0.0032,7.3e-05,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,0.00012,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +2690000,1,-0.01,-0.013,0.00033,0.027,-0.0054,-0.15,0.0091,-0.0031,-0.084,-0.0018,-0.0027,0.0001,0,0,-0.018,0,0,0,0,0,0,0,0,1.4e-06,0.0035,0.0035,8.1e-05,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,0.00012,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +2790000,1,-0.01,-0.013,0.00026,0.021,-0.0031,-0.14,0.0059,-0.0017,-0.081,-0.002,-0.003,0.00011,0,0,-0.022,0,0,0,0,0,0,0,0,1e-06,0.0027,0.0027,6.7e-05,0.77,0.77,0.096,0.16,0.16,0.089,0.0032,0.0032,9.7e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +2890000,1,-0.01,-0.013,0.00018,0.026,-0.005,-0.14,0.0082,-0.0021,-0.081,-0.0019,-0.003,0.00011,0,0,-0.025,0,0,0,0,0,0,0,0,1.1e-06,0.0029,0.0029,7.4e-05,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,9.7e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +2990000,1,-0.01,-0.013,0.00018,0.02,-0.0038,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,0.00011,0,0,-0.028,0,0,0,0,0,0,0,0,8.5e-07,0.0023,0.0023,6.2e-05,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,8e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +3090000,1,-0.01,-0.013,0.00038,0.025,-0.0068,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,0.00011,0,0,-0.031,0,0,0,0,0,0,0,0,9.3e-07,0.0025,0.0025,6.8e-05,0.82,0.82,0.095,0.22,0.22,0.086,0.0027,0.0027,8e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +3190000,1,-0.01,-0.013,0.00041,0.02,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,0.00011,0,0,-0.033,0,0,0,0,0,0,0,0,7.2e-07,0.002,0.002,5.8e-05,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,6.6e-05,0.04,0.04,0.031,0,0,0,0,0,0,0,0 +3290000,1,-0.01,-0.013,0.00043,0.024,-0.0067,-0.15,0.0073,-0.0021,-0.11,-0.0021,-0.0036,0.00011,0,0,-0.034,0,0,0,0,0,0,0,0,7.8e-07,0.0022,0.0022,6.4e-05,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,6.6e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +3390000,1,-0.0098,-0.013,0.00043,0.019,-0.0037,-0.15,0.005,-0.0014,-0.1,-0.0021,-0.0038,0.00011,0,0,-0.04,0,0,0,0,0,0,0,0,6e-07,0.0017,0.0017,5.5e-05,0.53,0.53,0.095,0.14,0.14,0.085,0.0019,0.0019,5.5e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +3490000,1,-0.0098,-0.013,0.00041,0.025,-0.0025,-0.15,0.0073,-0.0017,-0.1,-0.0021,-0.0038,0.00011,0,0,-0.044,0,0,0,0,0,0,0,0,6.5e-07,0.0019,0.0019,5.9e-05,0.65,0.65,0.095,0.19,0.19,0.086,0.0019,0.0019,5.5e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +3590000,1,-0.0096,-0.013,0.00035,0.022,-0.002,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,0.00011,0,0,-0.047,0,0,0,0,0,0,0,0,5e-07,0.0015,0.0015,5.1e-05,0.48,0.48,0.094,0.13,0.13,0.086,0.0016,0.0016,4.7e-05,0.04,0.04,0.026,0,0,0,0,0,0,0,0 +3690000,1,-0.0096,-0.013,0.00033,0.024,-0.0015,-0.15,0.0075,-0.0013,-0.11,-0.0022,-0.004,0.00011,0,0,-0.052,0,0,0,0,0,0,0,0,5.4e-07,0.0017,0.0017,5.6e-05,0.59,0.59,0.093,0.18,0.18,0.085,0.0016,0.0016,4.7e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +3790000,1,-0.0095,-0.012,0.00034,0.02,0.003,-0.15,0.0052,-0.00062,-0.11,-0.0022,-0.0042,0.00011,0,0,-0.055,0,0,0,0,0,0,0,0,4.3e-07,0.0014,0.0014,4.9e-05,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,4e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +3890000,1,-0.0094,-0.013,0.00041,0.022,0.0041,-0.14,0.0074,-0.00028,-0.11,-0.0022,-0.0042,0.00011,0,0,-0.059,0,0,0,0,0,0,0,0,4.7e-07,0.0015,0.0015,5.2e-05,0.54,0.54,0.091,0.17,0.17,0.086,0.0014,0.0014,4e-05,0.04,0.04,0.022,0,0,0,0,0,0,0,0 +3990000,1,-0.0094,-0.013,0.00047,0.027,0.0036,-0.14,0.0099,3.4e-05,-0.11,-0.0022,-0.0042,0.00011,0,0,-0.064,0,0,0,0,0,0,0,0,5.1e-07,0.0016,0.0016,5.6e-05,0.66,0.66,0.089,0.22,0.22,0.085,0.0014,0.0014,4e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +4090000,1,-0.0094,-0.012,0.00053,0.023,0.003,-0.12,0.0073,0.00029,-0.098,-0.0022,-0.0044,0.00011,0,0,-0.072,0,0,0,0,0,0,0,0,3.9e-07,0.0013,0.0013,4.9e-05,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,3.4e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +4190000,1,-0.0095,-0.012,0.00048,0.025,0.0026,-0.12,0.0098,0.00056,-0.1,-0.0022,-0.0044,0.00011,0,0,-0.074,0,0,0,0,0,0,0,0,4.3e-07,0.0015,0.0015,5.3e-05,0.6,0.6,0.086,0.21,0.21,0.086,0.0012,0.0012,3.4e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +4290000,1,-0.0095,-0.012,0.00049,0.023,0.0025,-0.12,0.0071,0.00049,-0.11,-0.0022,-0.0046,0.00011,0,0,-0.077,0,0,0,0,0,0,0,0,3.4e-07,0.0012,0.0012,4.7e-05,0.46,0.46,0.084,0.15,0.15,0.085,0.00095,0.00095,3e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +4390000,1,-0.0095,-0.012,0.00043,0.026,0.00086,-0.11,0.0096,0.00056,-0.094,-0.0022,-0.0046,0.00011,0,0,-0.083,0,0,0,0,0,0,0,0,3.6e-07,0.0013,0.0013,5e-05,0.55,0.55,0.081,0.2,0.2,0.084,0.00095,0.00095,3e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +4490000,1,-0.0095,-0.012,0.00049,0.022,0.0027,-0.11,0.0071,0.00048,-0.095,-0.0022,-0.0048,0.0001,0,0,-0.086,0,0,0,0,0,0,0,0,2.8e-07,0.001,0.001,4.5e-05,0.43,0.43,0.08,0.14,0.14,0.085,0.00079,0.00079,2.6e-05,0.04,0.04,0.015,0,0,0,0,0,0,0,0 +4590000,1,-0.0095,-0.012,0.00054,0.025,0.0014,-0.11,0.0095,0.00067,-0.098,-0.0022,-0.0048,0.0001,0,0,-0.089,0,0,0,0,0,0,0,0,3.1e-07,0.0011,0.0011,4.8e-05,0.51,0.51,0.077,0.19,0.19,0.084,0.00079,0.00079,2.6e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +4690000,1,-0.0095,-0.012,0.00047,0.019,0.0017,-0.1,0.0069,0.00048,-0.09,-0.0021,-0.005,0.0001,0,0,-0.093,0,0,0,0,0,0,0,0,2.4e-07,0.00092,0.00092,4.2e-05,0.39,0.39,0.074,0.14,0.14,0.083,0.00064,0.00064,2.3e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +4790000,1,-0.0094,-0.012,0.00056,0.017,0.0038,-0.099,0.0087,0.00079,-0.092,-0.0021,-0.005,0.0001,0,0,-0.095,0,0,0,0,0,0,0,0,2.6e-07,0.00099,0.00099,4.5e-05,0.47,0.47,0.073,0.18,0.18,0.084,0.00064,0.00064,2.3e-05,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +4890000,1,-0.0093,-0.012,0.00059,0.012,0.0014,-0.093,0.0058,0.00061,-0.088,-0.0021,-0.0051,0.0001,0,0,-0.099,0,0,0,0,0,0,0,0,2e-07,0.0008,0.0008,4e-05,0.36,0.36,0.07,0.13,0.13,0.083,0.00052,0.00052,2e-05,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +4990000,1,-0.0093,-0.012,0.00057,0.016,0.002,-0.085,0.0073,0.0008,-0.083,-0.0021,-0.0051,0.0001,0,0,-0.1,0,0,0,0,0,0,0,0,2.1e-07,0.00086,0.00086,4.3e-05,0.43,0.43,0.067,0.17,0.17,0.082,0.00052,0.00052,2e-05,0.04,0.04,0.01,0,0,0,0,0,0,0,0 +5090000,1,-0.0092,-0.012,0.00063,0.012,0.0025,-0.082,0.0051,0.00057,-0.081,-0.0021,-0.0052,0.0001,0,0,-0.1,0,0,0,0,0,0,0,0,1.6e-07,0.00069,0.00069,3.9e-05,0.33,0.33,0.065,0.12,0.12,0.082,0.00042,0.00042,1.8e-05,0.04,0.04,0.0098,0,0,0,0,0,0,0,0 +5190000,1,-0.009,-0.012,0.00067,0.012,0.0059,-0.08,0.0063,0.00097,-0.079,-0.0021,-0.0052,0.0001,0,0,-0.11,0,0,0,0,0,0,0,0,1.8e-07,0.00075,0.00075,4.1e-05,0.39,0.39,0.063,0.16,0.16,0.081,0.00042,0.00042,1.8e-05,0.04,0.04,0.0091,0,0,0,0,0,0,0,0 +5290000,1,-0.0089,-0.012,0.00072,0.01,0.0061,-0.068,0.0044,0.00094,-0.072,-0.0021,-0.0053,9.9e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.3e-07,0.0006,0.0006,3.7e-05,0.3,0.3,0.06,0.12,0.12,0.08,0.00034,0.00034,1.6e-05,0.04,0.04,0.0084,0,0,0,0,0,0,0,0 +5390000,1,-0.0088,-0.012,0.00071,0.0099,0.0096,-0.065,0.0054,0.0017,-0.067,-0.0021,-0.0053,9.9e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.4e-07,0.00065,0.00065,3.9e-05,0.36,0.36,0.057,0.15,0.15,0.079,0.00034,0.00034,1.6e-05,0.04,0.04,0.0078,0,0,0,0,0,0,0,0 +5490000,1,-0.0089,-0.012,0.0007,0.0091,0.011,-0.06,0.0037,0.0017,-0.065,-0.0021,-0.0054,9.7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,1.1e-07,0.00052,0.00052,3.6e-05,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,1.4e-05,0.04,0.04,0.0073,0,0,0,0,0,0,0,0 +5590000,1,-0.0089,-0.012,0.00062,0.01,0.015,-0.053,0.0048,0.0029,-0.058,-0.0021,-0.0054,9.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,1.2e-07,0.00056,0.00056,3.8e-05,0.32,0.32,0.053,0.15,0.15,0.078,0.00028,0.00028,1.4e-05,0.04,0.04,0.0067,0,0,0,0,0,0,0,0 +5690000,1,-0.0089,-0.011,0.00051,0.0095,0.015,-0.052,0.0034,0.0026,-0.055,-0.002,-0.0055,9.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,9.3e-08,0.00045,0.00045,3.4e-05,0.25,0.25,0.051,0.11,0.11,0.076,0.00022,0.00022,1.3e-05,0.04,0.04,0.0062,0,0,0,0,0,0,0,0 +5790000,1,-0.0088,-0.011,0.00046,0.011,0.017,-0.049,0.0044,0.0042,-0.053,-0.002,-0.0055,9.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,9.8e-08,0.00048,0.00048,3.6e-05,0.29,0.29,0.05,0.14,0.14,0.077,0.00022,0.00022,1.3e-05,0.04,0.04,0.0058,0,0,0,0,0,0,0,0 +5890000,1,-0.0088,-0.011,0.00048,0.011,0.015,-0.048,0.0033,0.0035,-0.056,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,7.7e-08,0.00039,0.00039,3.3e-05,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,1.2e-05,0.04,0.04,0.0054,0,0,0,0,0,0,0,0 +5990000,1,-0.0088,-0.012,0.00045,0.013,0.016,-0.041,0.0046,0.005,-0.05,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.3e-08,0.00041,0.00041,3.5e-05,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,1.2e-05,0.04,0.04,0.005,0,0,0,0,0,0,0,0 +6090000,1,-0.0088,-0.012,0.00026,0.013,0.017,-0.039,0.0059,0.0066,-0.047,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.8e-08,0.00044,0.00044,3.7e-05,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,1.2e-05,0.04,0.04,0.0047,0,0,0,0,0,0,0,0 +6190000,0.98,-0.0066,-0.013,0.19,0.0098,0.016,-0.037,0.0045,0.0054,-0.047,-0.0019,-0.0056,9.3e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,0.00034,0.00034,0.0015,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,1e-05,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 +6290000,0.98,-0.0066,-0.013,0.19,0.0083,0.018,-0.041,0.0054,0.0071,-0.053,-0.0019,-0.0056,9.3e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.6e-05,0.00034,0.00034,0.00095,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,1e-05,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,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,2.8e-05,0.00034,0.00034,0.00073,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,1e-05,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,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.2e-05,0.00034,0.00034,0.00057,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,1e-05,0.04,0.04,0.0036,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,9.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.9e-05,0.00035,0.00035,0.00047,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,1e-05,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,9.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.6e-05,0.00035,0.00035,0.0004,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,1e-05,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,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.4e-05,0.00036,0.00036,0.00036,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,1e-05,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,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.3e-05,0.00036,0.00036,0.00032,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,1e-05,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,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.2e-05,0.00037,0.00037,0.00028,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,1e-05,0.04,0.04,0.0026,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.026,-0.056,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.1e-05,0.00037,0.00037,0.00026,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,1e-05,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,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1e-05,0.00038,0.00038,0.00024,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,1e-05,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.042,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9.3e-06,0.00039,0.00039,0.00022,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,1e-05,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,8.8e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.8e-06,0.0004,0.0004,0.0002,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,1e-05,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,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.3e-06,0.00041,0.00041,0.00019,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,1e-05,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,9.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.8e-06,0.00042,0.00042,0.00018,0.6,0.61,0.025,1.2,1.2,0.062,0.00014,0.00014,1e-05,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.057,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.5e-06,0.00043,0.00043,0.00017,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 +7790000,0.98,-0.0056,-0.013,0.19,0.009,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.2e-06,0.00043,0.00043,0.00016,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,1e-05,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 +7890000,0.98,-0.0056,-0.013,0.19,0.0077,0.065,-0.025,0.016,0.064,-0.045,-0.0019,-0.0056,8.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.9e-06,0.00045,0.00045,0.00015,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,1e-05,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 +7990000,0.98,-0.0056,-0.013,0.19,0.0078,0.068,-0.021,0.016,0.07,-0.041,-0.0019,-0.0056,8.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-06,0.00045,0.00045,0.00014,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8090000,0.98,-0.0054,-0.013,0.19,0.0094,0.073,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,7.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-06,0.00047,0.00047,0.00014,0.92,0.92,0.022,2.1,2.1,0.059,0.00014,0.00014,1e-05,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,7.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-06,0.00048,0.00048,0.00013,1,1,0.021,2.4,2.4,0.058,0.00014,0.00014,1e-05,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,7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-06,0.00049,0.00049,0.00013,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,1e-05,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.087,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,6.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.8e-06,0.0005,0.0005,0.00012,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,1e-05,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,7.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.6e-06,0.00051,0.00051,0.00012,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,1e-05,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.11,-0.036,-0.0018,-0.0056,6.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.5e-06,0.00052,0.00052,0.00011,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,1e-05,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,6.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.4e-06,0.00053,0.00053,0.00011,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,1e-05,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.022,0.13,-0.035,-0.0018,-0.0056,6.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.2e-06,0.00054,0.00054,0.00011,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,1e-05,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.13,-0.029,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.1e-06,0.00054,0.00054,0.0001,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,1e-05,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,7.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5e-06,0.00056,0.00056,0.0001,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,1e-05,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,8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00055,0.00055,9.8e-05,1.7,1.7,0.016,5.4,5.5,0.053,0.00013,0.00013,1e-05,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,8.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.8e-06,0.00057,0.00057,9.5e-05,1.8,1.8,0.016,6.1,6.1,0.052,0.00013,0.00013,1e-05,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.0017,-0.0056,8.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.7e-06,0.00056,0.00055,9.3e-05,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,1e-05,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.0017,-0.0056,8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.7e-06,0.00057,0.00057,9.1e-05,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,1e-05,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.026,0.17,-0.027,-0.0017,-0.0056,8.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00056,0.00056,8.9e-05,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,1e-05,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,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00057,0.00057,8.7e-05,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,1e-05,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,6.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00055,0.00055,8.5e-05,2,2,0.014,8.1,8.1,0.05,0.00012,0.00012,1e-05,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.028,0.19,-0.028,-0.0017,-0.0056,4.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.4e-06,0.00057,0.00057,8.4e-05,2.1,2.2,0.014,8.9,8.9,0.05,0.00012,0.00012,1e-05,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.027,0.19,-0.029,-0.0016,-0.0056,4.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.4e-06,0.00054,0.00054,8.2e-05,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.0006,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.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00056,0.00056,8.1e-05,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,1e-05,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.028,0.19,-0.029,-0.0016,-0.0057,1.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00053,0.00053,8e-05,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,1e-05,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.029,0.2,-0.03,-0.0016,-0.0057,-3.5e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00055,0.00055,7.8e-05,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,1e-05,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.031,0.21,-0.029,-0.0016,-0.0057,3.8e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00057,0.00057,7.7e-05,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,9.9e-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.007,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,8.4e-06,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00059,0.00058,7.6e-05,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,9.9e-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.0084,0.0077,0.007,0.0015,0.00075,-0.023,-0.0016,-0.0057,-7.3e-06,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.0006,0.0006,7.5e-05,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,9.8e-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.0013,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,1.9e-06,0.00032,8.8e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00061,0.00061,7.4e-05,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10690000,0.98,-0.0052,-0.012,0.19,-0.00013,0.0067,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-3.7e-06,0.00032,9.5e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00063,0.00063,7.4e-05,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,9.8e-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,-6.3e-06,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00062,0.00062,7.3e-05,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,9.7e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10890000,0.98,-0.0053,-0.013,0.19,0.0018,0.0066,0.01,-0.0006,-0.0042,-0.018,-0.0016,-0.0057,1.2e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00064,0.00064,7.2e-05,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,9.7e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10990000,0.98,-0.0054,-0.013,0.19,0.0013,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,5.5e-06,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.0006,0.0006,7.2e-05,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,9.6e-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.0022,0.017,0.02,-0.00032,-0.0016,-0.0074,-0.0015,-0.0057,-1.5e-05,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00062,0.00062,7.1e-05,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,9.6e-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.0039,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,-2.7e-05,0.00065,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00055,0.00055,7e-05,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,9.5e-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.0041,0.018,0.026,0.0014,-2.5e-05,-0.00012,-0.0015,-0.0057,-3.3e-05,0.00065,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00057,0.00057,7e-05,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,9.5e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11390000,0.98,-0.006,-0.013,0.19,0.0025,0.015,0.016,0.00088,-0.00088,-0.0086,-0.0014,-0.0058,-3.2e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00049,0.00049,7e-05,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,9.4e-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.0015,0.016,0.02,0.001,0.00072,-0.0025,-0.0014,-0.0058,-2.8e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.0005,0.0005,6.9e-05,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,9.4e-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.0033,0.013,0.018,0.00083,-0.00036,-0.0036,-0.0013,-0.0058,-2.9e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00042,0.00042,6.9e-05,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,9.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.0038,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,-2.1e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00044,0.00044,6.8e-05,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,9.2e-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.0024,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,-6.2e-07,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00037,0.00037,6.8e-05,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,9.2e-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.0051,0.012,0.017,0.001,-0.0007,-0.0013,-0.0012,-0.0059,-2.8e-06,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00038,0.00038,6.8e-05,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,9.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11990000,0.98,-0.0069,-0.012,0.19,0.0081,0.012,0.015,0.0021,-0.0018,-0.0049,-0.0012,-0.0059,5.6e-06,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00032,0.00032,6.7e-05,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,9.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12090000,0.98,-0.0068,-0.012,0.19,0.0097,0.012,0.018,0.003,-0.00063,0.0011,-0.0012,-0.0059,7.2e-06,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00033,0.00033,6.7e-05,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12190000,0.98,-0.0067,-0.012,0.19,0.0077,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,7.5e-07,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00029,0.00029,6.7e-05,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,8.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12290000,0.98,-0.0068,-0.012,0.19,0.0054,0.011,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,-4.6e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.0003,0.0003,6.7e-05,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,8.9e-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,-4.1e-06,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00026,0.00026,6.7e-05,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12490000,0.98,-0.0069,-0.012,0.19,0.004,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,-3.9e-06,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00027,0.00027,6.6e-05,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,8.7e-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,-4.3e-06,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00024,0.00024,6.6e-05,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,8.7e-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.00065,0.019,0.004,-0.0013,0.0033,-0.0011,-0.006,-8.5e-07,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00025,0.00025,6.6e-05,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,8.6e-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,3.1e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00023,0.00023,6.6e-05,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,8.5e-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,5.3e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00024,0.00024,6.6e-05,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,8.5e-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,7.4e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,8.4e-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.0089,-0.0028,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,0.0001,0.0027,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00023,0.00023,6.6e-05,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13190000,0.98,-0.0073,-0.012,0.19,0.0038,-0.0045,0.019,0.00096,-0.0046,0.0091,-0.0011,-0.006,0.00012,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,8.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0054,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,0.00013,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,8.2e-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.00085,-0.0037,0.0091,-0.0011,-0.006,0.00012,0.0029,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4.1e-05,8.1e-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.0031,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,0.00013,0.003,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4.1e-05,8e-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.0076,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,0.00013,0.0032,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0088,0.048,0.048,0.044,3.9e-05,3.9e-05,8e-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.0076,-0.0035,0.017,0.0048,-0.0034,0.0064,-0.0011,-0.006,0.00015,0.0032,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.061,0.061,0.0085,0.056,0.056,0.044,3.9e-05,3.9e-05,7.9e-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.015,0.00072,0.017,0.0083,-0.00093,0.0059,-0.0011,-0.0059,0.00014,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,7.8e-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,0.00016,0.0035,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,7.7e-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,0.00019,0.0034,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,7.6e-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,0.00015,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,7.6e-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.01,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,0.00013,0.0036,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,7.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0017,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,0.00014,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,7.4e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,0.00015,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,7.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.0095,-0.0036,0.015,-0.0011,-0.006,0.00013,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,7.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.0079,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,0.00013,0.0031,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,7.2e-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.0046,0.011,-0.0011,-0.006,0.00014,0.0032,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,7.1e-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.0088,0.0025,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,0.00017,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.8e-05,7e-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,5e-05,0.023,0.006,0.00092,0.014,-0.0012,-0.006,0.00019,0.0033,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.8e-05,7e-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.0062,-0.0016,0.026,0.0047,-0.00069,0.017,-0.0012,-0.0061,0.00021,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,6.9e-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.00052,0.03,0.0054,-0.00084,0.019,-0.0012,-0.0061,0.00021,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.00019,6.5e-05,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.8e-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.0044,-0.0016,0.03,0.0042,-0.00076,0.021,-0.0012,-0.0061,0.0002,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.7e-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.005,-0.0027,0.03,0.0047,-0.00095,0.018,-0.0012,-0.0061,0.00023,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.6e-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.0052,-0.00028,0.029,0.0038,-0.00065,0.018,-0.0012,-0.0061,0.00023,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.6e-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.0046,-0.0028,0.029,0.0042,-0.00078,0.019,-0.0012,-0.0061,0.00023,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.5e-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.0063,-0.0047,0.018,-0.0011,-0.0061,0.00024,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.4e-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,0.00027,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,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.0091,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,0.0003,0.0038,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.2e-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.0075,0.03,0.0061,-0.0051,0.02,-0.0011,-0.0061,0.00028,0.004,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.2e-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.006,0.027,0.0048,-0.0039,0.019,-0.0012,-0.0061,0.00028,0.0042,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.1e-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.0073,0.024,0.005,-0.0046,0.019,-0.0012,-0.0061,0.00027,0.0044,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6e-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.0049,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,0.00026,0.0045,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6e-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.001,-0.0065,0.023,0.0025,-0.004,0.017,-0.0012,-0.0061,0.00027,0.0045,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,5.9e-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.0057,0.023,0.0036,-0.003,0.017,-0.0012,-0.0061,0.00029,0.0051,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00016,6.5e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,5.8e-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.0038,-0.0037,0.021,-0.0012,-0.0061,0.00028,0.005,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,5.7e-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,0.00028,0.0051,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,5.7e-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.0038,0.022,-0.0012,-0.0061,0.0003,0.0053,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,5.6e-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.0027,0.022,-0.0012,-0.0061,0.00031,0.0053,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16890000,0.98,-0.0074,-0.011,0.19,0.0088,-0.011,0.029,0.0042,-0.0038,0.02,-0.0012,-0.0061,0.00033,0.0056,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,5.4e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16990000,0.98,-0.0074,-0.011,0.19,0.0085,-0.011,0.029,0.004,-0.0028,0.019,-0.0013,-0.0061,0.00034,0.0062,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,5.4e-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,0.00033,0.0064,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00015,6.5e-05,0.04,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,5.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.0075,0.021,-0.0012,-0.0061,0.00031,0.0063,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,5.2e-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,0.00029,0.0065,0.002,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,5.2e-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,0.00031,0.0073,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,5.1e-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.0047,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,0.00031,0.0074,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00015,0.00015,6.5e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,5e-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.00086,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,0.00031,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17690000,0.98,-0.0075,-0.011,0.19,-9e-05,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,0.00031,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.4e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,4.9e-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.0026,-0.014,0.029,0.0035,-0.0062,0.028,-0.0014,-0.006,0.00031,0.0076,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00013,6.5e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,4.8e-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,0.00032,0.0075,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.4e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,4.8e-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,0.00032,0.0079,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,4.7e-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.0098,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,0.00032,0.0082,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,4.6e-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,0.00035,0.0088,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,4.6e-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,0.00035,0.009,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,4.5e-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,0.00034,0.0096,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00012,6.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,4.5e-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.008,0.026,0.0069,-0.0031,0.028,-0.0014,-0.006,0.00035,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,4.4e-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,0.00033,0.0095,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,4.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,0.00035,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,4.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,0.00034,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,4.2e-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.0056,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,0.00033,0.01,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,4.2e-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.0027,-0.0057,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,0.00033,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19090000,0.98,-0.007,-0.011,0.19,0.00066,-0.0062,0.023,0.0058,-0.0031,0.022,-0.0015,-0.006,0.00034,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,4.1e-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.00084,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,0.00032,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0057,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,0.00031,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,3.9e-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.0021,-0.0022,0.024,0.004,-0.0012,0.02,-0.0015,-0.006,0.0003,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,3.9e-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.0022,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,0.00029,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,3.8e-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.0051,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,0.00028,0.012,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,3.8e-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,0.00029,0.012,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,3.7e-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.0022,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,0.00027,0.012,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,3.7e-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,0.00027,0.013,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,3.6e-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.00091,0.0097,-0.0015,-0.0059,0.00027,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,3.6e-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.0041,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,0.00026,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.0001,6.2e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,3.5e-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.0009,0.013,-0.0015,-0.0059,0.00025,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,3.5e-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,0.00024,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.1e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00077,0.014,-0.0015,-0.0059,0.00025,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.1e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.0059,-0.00094,0.012,-0.0015,-0.0059,0.00025,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.1e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,3.4e-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.00079,0.011,-0.0015,-0.0059,0.00027,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,3.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.0021,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,0.00025,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,3.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.00042,0.0055,0.0048,-0.0008,0.0097,-0.0015,-0.0059,0.00025,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.7e-05,6.1e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,3.2e-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.00012,0.0034,-0.0015,-0.0059,0.00025,0.015,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.9e-05,9.8e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,3.2e-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.00052,-0.011,-0.0015,-0.0059,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.7e-05,9.6e-05,6e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,3.1e-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,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.6e-05,6e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,3.1e-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,0.00025,0.015,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.5e-05,9.4e-05,6e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,3.1e-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,0.00023,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.6e-05,9.5e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,0.00023,0.015,0.0009,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.4e-05,9.2e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,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,0.00024,0.015,0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.4e-05,9.3e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.008,0.016,-0.38,-0.0014,-0.0059,0.00025,0.015,0.00074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9e-05,5.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,2.9e-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,0.00026,0.015,0.00057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9.1e-05,5.9e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,2.9e-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,0.00027,0.016,0.00037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,2.8e-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,0.00026,0.016,0.00024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,2.8e-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.00036,0.017,-0.89,-0.0014,-0.0058,0.00027,0.015,0.00047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,2.8e-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,0.00028,0.016,0.00034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-06,1.1e-06,2.7e-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,0.00029,0.016,0.00037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.6e-05,8.5e-05,5.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0078,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,0.00029,0.016,0.00028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.7e-05,8.5e-05,5.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22390000,0.98,-0.0073,-0.01,0.19,0.0066,-0.0018,-1.4,0.013,0.0041,-1.5,-0.0014,-0.0058,0.00027,0.016,-9.8e-05,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.3e-05,5.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22490000,0.98,-0.0074,-0.011,0.19,0.01,-0.0078,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,0.00026,0.016,-0.00017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.4e-05,5.8e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,0.00027,0.016,-0.00033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.3e-05,8.2e-05,5.8e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0073,-1.9,-0.0014,-0.0058,0.00026,0.016,-0.00041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.4e-05,8.2e-05,5.8e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-07,9.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,0.00025,0.016,-0.00052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,2.5e-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.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,0.00027,0.016,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,2.4e-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,0.00028,0.017,-0.00074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,2.4e-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,0.00028,0.017,-0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,2.4e-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,0.00027,0.017,-0.00092,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-07,7.9e-07,2.4e-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,0.00027,0.017,-0.00097,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,2.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,0.00026,0.017,-0.00071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.6e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-07,7.5e-07,2.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,0.00027,0.017,-0.00075,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.8e-05,5.6e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0059,0.00027,0.017,-0.00088,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0059,0.00028,0.017,-0.0009,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.6e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,0.00029,0.017,-0.00091,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23890000,0.98,-0.014,-0.021,0.18,0.052,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,0.0003,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.12,-0.089,-3.6,-0.0014,-0.0058,0.00029,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,0.00029,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00031,0.019,-0.0031,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00033,0.019,-0.0031,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0038,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24690000,0.98,-0.011,-0.015,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0038,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0044,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0044,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00031,0.019,-0.0056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00031,0.019,-0.0064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,0.00029,0.018,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00029,0.019,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,0.00029,0.019,-0.0072,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-07,4.8e-07,1.7e-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.028,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0072,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-07,4.8e-07,1.7e-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,0.00026,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.014,0.00051,0.15,-0.083,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.98,-0.0098,-0.012,0.18,-0.032,-0.0064,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00025,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0032,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00024,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0047,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,0.00023,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0098,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.2e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.98,-0.008,-0.011,0.18,-0.051,0.017,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-07,4.2e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,0.0002,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.036,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27290000,0.98,-0.0076,-0.013,0.18,-0.073,0.042,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27390000,0.98,-0.009,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,0.00018,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.029,-3.5,-0.0016,-0.0058,0.00016,0.02,-0.0095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,0.00016,0.02,-0.0096,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27690000,0.98,-0.009,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,0.00016,0.02,-0.0097,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,4.9e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,0.00016,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27890000,0.98,-0.0073,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,0.00015,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0047,-3,-0.0016,-0.0058,0.00016,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-07,3.7e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0023,-0.0043,-3,-0.0016,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,0.00016,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0044,-2.8,-0.0015,-0.0058,0.00016,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,0.00016,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1.3e-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.0084,-2.7,-0.0015,-0.0058,0.00016,0.02,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,0.00016,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1.2e-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,0.00016,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1.2e-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,0.00016,0.02,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,0.00016,0.02,-0.0087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-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,0.00016,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,0.00016,0.02,-0.0091,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,0.00017,0.02,-0.0091,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0093,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-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,0.00019,0.02,-0.0095,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1.1e-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.074,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,0.0002,0.02,-0.0097,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-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,0.0002,0.02,-0.0099,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,0.0002,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-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,0.00019,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-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,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1.1e-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,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-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,0.0002,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.5e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +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,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-07,3e-07,1e-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,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31090000,0.98,-0.0062,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,0.00019,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-07,3e-07,1e-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.021,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,0.00021,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,0.00021,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.9e-07,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,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.7e-07,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.0067,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,0.00021,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.6e-07,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.0057,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,0.00022,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.6e-07,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.0031,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,0.00022,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.4e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,9.5e-07,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.00081,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00023,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31990000,0.98,-0.0062,-0.015,0.18,-0.0001,0.00015,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32090000,0.98,-0.0065,-0.014,0.18,-0.00064,-0.0033,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32190000,0.98,-0.0067,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0092,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00023,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32390000,0.98,-0.0067,-0.015,0.18,0.013,-0.01,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,7.9e-05,4.3e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-07,2.7e-07,9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.8e-05,4.3e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-07,2.7e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.9e-05,4.3e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-07,2.7e-07,8.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.7e-05,7.6e-05,4.2e-05,0.019,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,8.7e-07,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.0021,-0.011,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.7e-05,7.6e-05,4.2e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,8.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0011,-0.024,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,8.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0092,-0.031,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,8.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.7e-05,6.6e-05,4.2e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-07,2.6e-07,8.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.7e-05,6.6e-05,4.2e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-07,2.6e-07,8.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,8.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,6.1e-05,6e-05,4.2e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-07,2.6e-07,8.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.3e-05,5.3e-05,4.2e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,8.2e-07,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 +33690000,0.98,-0.0077,-0.013,0.18,0.00078,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.4e-05,5.3e-05,4.1e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,8.1e-07,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,0.00024,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,8.1e-07,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,0.00025,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,8e-07,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,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,7.9e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.6e-05,4.1e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,7.8e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.7e-05,4.1e-05,0.055,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,7.8e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.073,-0.01,-0.11,-0.0014,-0.0056,0.00024,0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.3e-05,3.3e-05,4.1e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,7.7e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00024,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.4e-05,3.3e-05,4.1e-05,0.053,0.054,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,7.7e-07,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.0087,-0.081,-0.0014,-0.0056,0.00024,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-07,2.6e-07,7.6e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0027,1.7,0.071,-0.0091,0.038,-0.0014,-0.0056,0.00024,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4e-05,0.047,0.048,0.006,0.052,0.052,0.032,2.6e-07,2.6e-07,7.6e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,2.9e-05,4e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-07,2.6e-07,7.5e-07,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.0043,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,0.00023,0.018,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,3e-05,4e-05,0.044,0.044,0.0061,0.052,0.052,0.032,2.6e-07,2.6e-07,7.4e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index 3c5f06e306..f6eea4af23 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -50,12 +50,15 @@ public: SensorSimulator _sensor_simulator; EkfWrapper _ekf_wrapper; - const float _init_tilt_period = 0.3f; // seconds + const float _init_tilt_period = 0.7f; // seconds - // GTests is calling this + // Setup the Ekf with synthetic measurements void SetUp() override { + // first init, then manually set in air and at rest (default for a real vehicle) _ekf->init(0); + _ekf->set_in_air_status(false); + _ekf->set_vehicle_at_rest(true); } // Use this method to clean up any memory, network etc. after each test @@ -66,28 +69,19 @@ public: void initializedOrienationIsMatchingGroundTruth(Quatf true_quaternion) { const Quatf quat_est = _ekf->getQuaternion(); - const float precision = 0.0002f; // TODO: this is only required for the pitch90 test to pass - EXPECT_TRUE(matrix::isEqual(quat_est, true_quaternion, precision)) + EXPECT_TRUE(matrix::isEqual(quat_est, true_quaternion)) << "quat est = " << quat_est(0) << ", " << quat_est(1) << ", " << quat_est(2) << ", " << quat_est(3) << "\nquat true = " << true_quaternion(0) << ", " << true_quaternion(1) << ", " << true_quaternion(2) << ", " << true_quaternion(3); } - void validStateAfterOrientationInitialization() - { - quaternionVarianceBigEnoughAfterOrientationInitialization(); - velocityAndPositionCloseToZero(); - velocityAndPositionVarianceBigEnoughAfterOrientationInitialization(); - } - - void quaternionVarianceBigEnoughAfterOrientationInitialization() + void quaternionVarianceBigEnoughAfterOrientationInitialization(float quat_variance_limit = 0.00001f) { const matrix::Vector4f quat_variance = _ekf_wrapper.getQuaternionVariance(); - const float quat_variance_limit = 0.0001f; - EXPECT_TRUE(quat_variance(1) > quat_variance_limit) << "quat_variance(1)" << quat_variance(1); - EXPECT_TRUE(quat_variance(2) > quat_variance_limit) << "quat_variance(2)" << quat_variance(2); - EXPECT_TRUE(quat_variance(3) > quat_variance_limit) << "quat_variance(3)" << quat_variance(3); + EXPECT_TRUE(quat_variance(1) > quat_variance_limit) << "quat_variance(1): " << quat_variance(1); + EXPECT_TRUE(quat_variance(2) > quat_variance_limit) << "quat_variance(2): " << quat_variance(2); + EXPECT_TRUE(quat_variance(3) > quat_variance_limit) << "quat_variance(3): " << quat_variance(3); } void velocityAndPositionCloseToZero() @@ -101,20 +95,22 @@ public: << "vel = " << vel(0) << ", " << vel(1) << ", " << vel(2); } - void velocityAndPositionVarianceBigEnoughAfterOrientationInitialization() + void velocityVarianceBigEnoughAfterOrientationInitialization(float vel_variance_limit) { - const Vector3f pos_var = _ekf->getPositionVariance(); const Vector3f vel_var = _ekf->getVelocityVariance(); - const float pos_variance_limit = 0.01f; // Fake fusion obs var when at rest - EXPECT_TRUE(pos_var(0) > pos_variance_limit) << "pos_var(0)" << pos_var(0); - EXPECT_TRUE(pos_var(1) > pos_variance_limit) << "pos_var(1)" << pos_var(1); - EXPECT_TRUE(pos_var(2) > pos_variance_limit) << "pos_var(2)" << pos_var(2); + EXPECT_TRUE(vel_var(0) > vel_variance_limit) << "vel_var(0): " << vel_var(0); + EXPECT_TRUE(vel_var(1) > vel_variance_limit) << "vel_var(1): " << vel_var(1); + EXPECT_TRUE(vel_var(2) > vel_variance_limit) << "vel_var(2): " << vel_var(2); + } - const float vel_variance_limit = 0.0001f; // zero velocity update obs var when at rest - EXPECT_TRUE(vel_var(0) > vel_variance_limit) << "vel_var(0)" << vel_var(0); - EXPECT_TRUE(vel_var(1) > vel_variance_limit) << "vel_var(1)" << vel_var(1); - EXPECT_TRUE(vel_var(2) > vel_variance_limit) << "vel_var(2)" << vel_var(2); + void positionVarianceBigEnoughAfterOrientationInitialization(float pos_variance_limit) + { + const Vector3f pos_var = _ekf->getPositionVariance(); + + EXPECT_TRUE(pos_var(0) > pos_variance_limit) << "pos_var(0): " << pos_var(0); + EXPECT_TRUE(pos_var(1) > pos_variance_limit) << "pos_var(1): " << pos_var(1); + EXPECT_TRUE(pos_var(2) > pos_variance_limit) << "pos_var(2): " << pos_var(2); } void learningCorrectAccelBias() @@ -144,8 +140,46 @@ TEST_F(EkfInitializationTest, initializeWithZeroTilt) _sensor_simulator.simulateOrientation(quat_sim); _sensor_simulator.runSeconds(_init_tilt_period); + EXPECT_TRUE(_ekf->control_status_flags().vehicle_at_rest); + EXPECT_FALSE(_ekf->control_status_flags().in_air); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); + initializedOrienationIsMatchingGroundTruth(quat_sim); - validStateAfterOrientationInitialization(); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + // Fake position fusion obs var when at rest sq(0.01f) + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); + + _sensor_simulator.runSeconds(1.f); + learningCorrectAccelBias(); +} + +TEST_F(EkfInitializationTest, initializeWithZeroTiltNotAtRest) +{ + const float pitch = math::radians(0.0f); + const float roll = math::radians(0.0f); + const Eulerf euler_angles_sim(roll, pitch, 0.0f); + const Quatf quat_sim(euler_angles_sim); + + _ekf->set_in_air_status(true); + _ekf->set_vehicle_at_rest(false); + _sensor_simulator.simulateOrientation(quat_sim); + //_sensor_simulator.runSeconds(_init_tilt_period); + _sensor_simulator.runSeconds(7); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); + + initializedOrienationIsMatchingGroundTruth(quat_sim); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); // Fake position fusion obs var when at rest sq(0.5f) + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); _sensor_simulator.runSeconds(1.f); learningCorrectAccelBias(); @@ -222,8 +256,20 @@ TEST_F(EkfInitializationTest, initializeHeadingWithZeroTilt) _sensor_simulator.simulateOrientation(quat_sim); _sensor_simulator.runSeconds(_init_tilt_period); + EXPECT_TRUE(_ekf->control_status_flags().vehicle_at_rest); + EXPECT_FALSE(_ekf->control_status_flags().in_air); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); + EXPECT_TRUE(_ekf->control_status_flags().yaw_align); + initializedOrienationIsMatchingGroundTruth(quat_sim); - validStateAfterOrientationInitialization(); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + // Fake position fusion obs var when at rest sq(0.01f) + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); _sensor_simulator.runSeconds(1.f); learningCorrectAccelBias(); @@ -239,8 +285,44 @@ TEST_F(EkfInitializationTest, initializeWithTilt) _sensor_simulator.simulateOrientation(quat_sim); _sensor_simulator.runSeconds(_init_tilt_period); + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); + EXPECT_TRUE(_ekf->control_status_flags().yaw_align); + initializedOrienationIsMatchingGroundTruth(quat_sim); - validStateAfterOrientationInitialization(); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + // Fake position fusion obs var when at rest sq(0.01f) + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); + + _sensor_simulator.runSeconds(1.f); + learningCorrectAccelBias(); +} + +TEST_F(EkfInitializationTest, initializeWithTiltNotAtRest) +{ + const float pitch = math::radians(30.0f); + const float roll = math::radians(60.0f); + const Eulerf euler_angles_sim(roll, pitch, 0.0f); + const Quatf quat_sim(euler_angles_sim); + + _ekf->set_in_air_status(true); + _ekf->set_vehicle_at_rest(false); + _sensor_simulator.simulateOrientation(quat_sim); + //_sensor_simulator.runSeconds(_init_tilt_period); + _sensor_simulator.runSeconds(7); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); + + initializedOrienationIsMatchingGroundTruth(quat_sim); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + positionVarianceBigEnoughAfterOrientationInitialization(0.01f); + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); _sensor_simulator.runSeconds(1.f); learningCorrectAccelBias(); @@ -253,13 +335,25 @@ TEST_F(EkfInitializationTest, initializeWithPitch90) const Eulerf euler_angles_sim(roll, pitch, 0.0f); const Quatf quat_sim(euler_angles_sim); + _ekf->set_in_air_status(false); + _ekf->set_vehicle_at_rest(true); _sensor_simulator.simulateOrientation(quat_sim); - _sensor_simulator.runSeconds(_init_tilt_period); + //_sensor_simulator.runSeconds(_init_tilt_period); + _sensor_simulator.runSeconds(10); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); - initializedOrienationIsMatchingGroundTruth(quat_sim); // TODO: Quaternion Variance is smaller and vel x is larger // in this case than in the other cases - validStateAfterOrientationInitialization(); + + initializedOrienationIsMatchingGroundTruth(quat_sim); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + // Fake position fusion obs var when at rest sq(0.01f) + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); _sensor_simulator.runSeconds(1.f); learningCorrectAccelBias(); @@ -272,11 +366,22 @@ TEST_F(EkfInitializationTest, initializeWithRoll90) const Eulerf euler_angles_sim(roll, pitch, 0.0f); const Quatf quat_sim(euler_angles_sim); + _ekf->set_in_air_status(false); + _ekf->set_vehicle_at_rest(true); _sensor_simulator.simulateOrientation(quat_sim); - _sensor_simulator.runSeconds(_init_tilt_period); + //_sensor_simulator.runSeconds(_init_tilt_period); + _sensor_simulator.runSeconds(10); + + EXPECT_TRUE(_ekf->control_status_flags().tilt_align); initializedOrienationIsMatchingGroundTruth(quat_sim); - validStateAfterOrientationInitialization(); + quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + + velocityAndPositionCloseToZero(); + + // Fake position fusion obs var when at rest sq(0.01f) + positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); + velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f); _sensor_simulator.runSeconds(1.f); learningCorrectAccelBias();