From 64add171786255e3db4cd2fda0b435ac35b49332 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 2 Oct 2024 09:54:08 +0200 Subject: [PATCH 01/11] ekf2: store position state as lat/lon/alt The position error state is still defined in a body-fixed NED frame but the position state itself is latitude-longitude-altitude. --- msg/EstimatorAidSource2d.msg | 2 +- src/modules/ekf2/EKF/CMakeLists.txt | 1 + .../aux_global_position.cpp | 39 ++-- .../barometer/baro_height_control.cpp | 14 +- .../external_vision/ev_height_control.cpp | 14 +- .../external_vision/ev_pos_control.cpp | 16 +- .../EKF/aid_sources/fake_height_control.cpp | 8 +- .../ekf2/EKF/aid_sources/fake_pos_control.cpp | 14 +- .../aid_sources/gnss/gnss_height_control.cpp | 18 +- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 15 +- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 28 +-- .../aid_sources/magnetometer/mag_control.cpp | 9 +- .../optical_flow/optical_flow_control.cpp | 6 +- .../optical_flow/optical_flow_fusion.cpp | 3 +- .../range_finder/range_height_control.cpp | 4 +- src/modules/ekf2/EKF/ekf.cpp | 63 +++--- src/modules/ekf2/EKF/ekf.h | 51 +++-- src/modules/ekf2/EKF/ekf_helper.cpp | 188 ++++++++++-------- src/modules/ekf2/EKF/estimator_interface.h | 34 +++- .../ekf2/EKF/lat_lon_alt/CMakeLists.txt | 1 + .../ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp | 154 ++++++++++++++ .../ekf2/EKF/lat_lon_alt/test_lat_lon_alt.cpp | 107 ++++++++++ .../EKF/output_predictor/output_predictor.cpp | 49 ++--- .../EKF/output_predictor/output_predictor.h | 18 +- src/modules/ekf2/EKF/position_fusion.cpp | 135 +++++++++---- src/modules/ekf2/EKF/terrain_control.cpp | 4 +- src/modules/ekf2/EKF2.cpp | 10 +- src/modules/ekf2/test/test_EKF_airspeed.cpp | 19 +- src/modules/ekf2/test/test_EKF_basics.cpp | 15 +- src/modules/ekf2/test/test_EKF_flow.cpp | 46 +++++ src/modules/ekf2/test/test_EKF_gps.cpp | 2 +- .../ekf2/test/test_EKF_height_fusion.cpp | 19 +- .../ekf2/test/test_EKF_yaw_estimator.cpp | 13 +- 33 files changed, 777 insertions(+), 342 deletions(-) create mode 100644 src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt create mode 100644 src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp create mode 100644 src/modules/ekf2/EKF/lat_lon_alt/test_lat_lon_alt.cpp diff --git a/msg/EstimatorAidSource2d.msg b/msg/EstimatorAidSource2d.msg index 14e3ac3f846d..8f3a9f0cda11 100644 --- a/msg/EstimatorAidSource2d.msg +++ b/msg/EstimatorAidSource2d.msg @@ -7,7 +7,7 @@ uint32 device_id uint64 time_last_fuse -float32[2] observation +float64[2] observation float32[2] observation_variance float32[2] innovation diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 954123b250f5..27804ebcd88a 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -33,6 +33,7 @@ add_subdirectory(bias_estimator) add_subdirectory(output_predictor) +add_subdirectory(lat_lon_alt) set(EKF_LIBS) set(EKF_SRCS) diff --git a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp index dc8f318c9778..973a70dbe439 100644 --- a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp +++ b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp @@ -74,24 +74,21 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed } estimator_aid_source2d_s aid_src{}; - Vector2f position; - - if (ekf.global_origin_valid()) { - position = ekf.global_origin().project(sample.latitude, sample.longitude); - //const float hgt = ekf.getEkfGlobalOriginAltitude() - (float)sample.altitude; - // relax the upper observation noise limit which prevents bad measurements perturbing the position estimate - float pos_noise = math::max(sample.eph, _param_ekf2_agp_noise.get(), 0.01f); - const float pos_var = sq(pos_noise); - const Vector2f pos_obs_var(pos_var, pos_var); - - ekf.updateAidSourceStatus(aid_src, - sample.time_us, // sample timestamp - position, // observation - pos_obs_var, // observation variance - Vector2f(ekf.state().pos) - position, // innovation - Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance - math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate - } + const LatLonAlt position(sample.latitude, sample.longitude, sample.altitude_amsl); + const Vector2f innovation = (ekf.getLatLonAlt() - position).xy(); // altitude measurements are not used + + // relax the upper observation noise limit which prevents bad measurements perturbing the position estimate + float pos_noise = math::max(sample.eph, _param_ekf2_agp_noise.get(), 0.01f); + const float pos_var = sq(pos_noise); + const Vector2f pos_obs_var(pos_var, pos_var); + + ekf.updateAidSourceStatus(aid_src, + sample.time_us, // sample timestamp + matrix::Vector2d(sample.latitude, sample.longitude), // observation + pos_obs_var, // observation variance + innovation, // innovation + Vector2f(ekf.getPositionVariance()) + pos_obs_var, // innovation variance + math::max(_param_ekf2_agp_gate.get(), 1.f)); // innovation gate const bool starting_conditions = PX4_ISFINITE(sample.latitude) && PX4_ISFINITE(sample.longitude) && ekf.control_status_flags().yaw_align; @@ -113,8 +110,8 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed } else { // Try to initialize using measurement - if (ekf.setEkfGlobalOriginFromCurrentPos(sample.latitude, sample.longitude, sample.altitude_amsl, sample.eph, - sample.epv)) { + if (ekf.resetGlobalPositionTo(sample.latitude, sample.longitude, sample.altitude_amsl, sample.eph, + sample.epv)) { ekf.enableControlStatusAuxGpos(); _reset_counters.lat_lon = sample.lat_lon_reset_counter; _state = State::active; @@ -131,7 +128,7 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed if (isTimedOut(aid_src.time_last_fuse, imu_delayed.time_us, ekf._params.no_aid_timeout_max) || (_reset_counters.lat_lon != sample.lat_lon_reset_counter)) { - ekf.resetHorizontalPositionTo(Vector2f(aid_src.observation), Vector2f(aid_src.observation_variance)); + ekf.resetHorizontalPositionTo(sample.latitude, sample.longitude, Vector2f(aid_src.observation_variance)); ekf.resetAidSourceStatusZeroInnovation(aid_src); diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index f6ab66f73660..0f5bcd610c91 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -73,7 +73,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) if (_baro_counter <= _obs_buffer_length) { // Initialize the pressure offset (included in the baro bias) - bias_est.setBias(_state.pos(2) + _baro_lpf.getState()); + bias_est.setBias(-_gpos.altitude() + _baro_lpf.getState()); } } @@ -106,7 +106,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) if (measurement_valid) { bias_est.setMaxStateNoise(sqrtf(measurement_var)); bias_est.setProcessNoiseSpectralDensity(_params.baro_bias_nsd); - bias_est.fuseBias(measurement - (-_state.pos(2)), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); + bias_est.fuseBias(measurement - _gpos.altitude(), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); } // determine if we should use height aiding @@ -131,8 +131,8 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_baro = true; - resetVerticalPositionTo(-(_baro_lpf.getState() - bias_est.getBias()), measurement_var); - bias_est.setBias(_state.pos(2) + _baro_lpf.getState()); + resetHeightTo(_baro_lpf.getState() - bias_est.getBias(), measurement_var); + bias_est.setBias(-_gpos.altitude() + _baro_lpf.getState()); // reset vertical velocity if no valid sources available if (!isVerticalVelocityAidingActive()) { @@ -163,12 +163,12 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) _height_sensor_ref = HeightSensor::BARO; _information_events.flags.reset_hgt_to_baro = true; - resetVerticalPositionTo(-(_baro_lpf.getState() - bias_est.getBias()), measurement_var); - bias_est.setBias(_state.pos(2) + _baro_lpf.getState()); + resetAltitudeTo(measurement, measurement_var); + bias_est.reset(); } else { ECL_INFO("starting %s height fusion", HGT_SRC_NAME); - bias_est.setBias(_state.pos(2) + _baro_lpf.getState()); + bias_est.setBias(-_gpos.altitude() + _baro_lpf.getState()); } aid_src.time_last_fuse = imu_sample.time_us; diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index 440c0fe7acf6..f62be7575fdc 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -99,7 +99,7 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp if (measurement_valid && quality_sufficient) { bias_est.setMaxStateNoise(sqrtf(measurement_var)); bias_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd); - bias_est.fuseBias(measurement - _state.pos(2), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); + bias_est.fuseBias(measurement + _gpos.altitude(), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); } const bool continuing_conditions_passing = (_params.ev_ctrl & static_cast(EvCtrl::VPOS)) @@ -117,11 +117,11 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp if (_height_sensor_ref == HeightSensor::EV) { _information_events.flags.reset_hgt_to_ev = true; - resetVerticalPositionTo(measurement, measurement_var); + resetHeightTo(-measurement, measurement_var); bias_est.reset(); } else { - bias_est.setBias(-_state.pos(2) + measurement); + bias_est.setBias(_gpos.altitude() + measurement); } aid_src.time_last_fuse = _time_delayed_us; @@ -146,8 +146,8 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp // All height sources are failing ECL_WARN("%s fusion reset required, all height sources failing", AID_SRC_NAME); _information_events.flags.reset_hgt_to_ev = true; - resetVerticalPositionTo(measurement - bias_est.getBias(), measurement_var); - bias_est.setBias(-_state.pos(2) + measurement); + resetHeightTo(-measurement - bias_est.getBias(), measurement_var); + bias_est.setBias(_gpos.altitude() + measurement); aid_src.time_last_fuse = _time_delayed_us; @@ -170,14 +170,14 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp if (_params.height_sensor_ref == static_cast(HeightSensor::EV)) { ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME); _information_events.flags.reset_hgt_to_ev = true; - resetVerticalPositionTo(measurement, measurement_var); + resetHeightTo(-measurement, measurement_var); _height_sensor_ref = HeightSensor::EV; bias_est.reset(); } else { ECL_INFO("starting %s fusion", AID_SRC_NAME); - bias_est.setBias(-_state.pos(2) + measurement); + bias_est.setBias(_gpos.altitude() + measurement); } aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp index 590a289da394..266b4cf5482b 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_pos_control.cpp @@ -137,6 +137,8 @@ void Ekf::controlEvPosFusion(const imuSample &imu_sample, const extVisionSample #endif // CONFIG_EKF2_GNSS + const Vector2f position_estimate = getLocalHorizontalPosition(); + const Vector2f measurement{pos(0), pos(1)}; const Vector2f measurement_var{ @@ -150,7 +152,7 @@ void Ekf::controlEvPosFusion(const imuSample &imu_sample, const extVisionSample if (!bias_fusion_was_active && _ev_pos_b_est.fusionActive()) { if (quality_sufficient) { // reset the bias estimator - _ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement); + _ev_pos_b_est.setBias(-position_estimate + measurement); } else if (isOtherSourceOfHorizontalAidingThan(_control_status.flags.ev_pos)) { // otherwise stop EV position, when quality is good again it will restart with reset bias @@ -165,7 +167,7 @@ void Ekf::controlEvPosFusion(const imuSample &imu_sample, const extVisionSample ev_sample.time_us, // sample timestamp position, // observation pos_obs_var, // observation variance - Vector2f(_state.pos) - position, // innovation + position_estimate - position, // innovation Vector2f(getStateVariance()) + pos_obs_var, // innovation variance math::max(_params.ev_pos_innov_gate, 1.f)); // innovation gate @@ -174,7 +176,7 @@ void Ekf::controlEvPosFusion(const imuSample &imu_sample, const extVisionSample if (measurement_valid && quality_sufficient) { _ev_pos_b_est.setMaxStateNoise(Vector2f(sqrtf(measurement_var(0)), sqrtf(measurement_var(1)))); _ev_pos_b_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd); // TODO - _ev_pos_b_est.fuseBias(measurement - Vector2f(_state.pos.xy()), + _ev_pos_b_est.fuseBias(measurement - position_estimate, measurement_var + Vector2f(getStateVariance())); } @@ -213,7 +215,7 @@ void Ekf::startEvPosFusion(const Vector2f &measurement, const Vector2f &measurem // TODO: (_params.position_sensor_ref == PositionSensor::EV) if (_control_status.flags.gps) { ECL_INFO("starting %s fusion", EV_AID_SRC_NAME); - _ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement); + _ev_pos_b_est.setBias(-getLocalHorizontalPosition() + measurement); _ev_pos_b_est.setFusionActive(); } else { @@ -245,7 +247,7 @@ void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measure _ev_pos_b_est.reset(); } else { - _ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement); + _ev_pos_b_est.setBias(-getLocalHorizontalPosition() + measurement); } aid_src.time_last_fuse = _time_delayed_us; @@ -275,14 +277,14 @@ void Ekf::updateEvPosFusion(const Vector2f &measurement, const Vector2f &measure if (_control_status.flags.gps && !pos_xy_fusion_failing) { // reset EV position bias - _ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement); + _ev_pos_b_est.setBias(-Vector2f(getLocalHorizontalPosition()) + measurement); } else { _information_events.flags.reset_pos_to_vision = true; if (_control_status.flags.gps) { resetHorizontalPositionTo(measurement - _ev_pos_b_est.getBias(), measurement_var + _ev_pos_b_est.getBiasVar()); - _ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement); + _ev_pos_b_est.setBias(-getLocalHorizontalPosition() + measurement); } else { resetHorizontalPositionTo(measurement, measurement_var); diff --git a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp index d10fe57d4413..4ff4e67d6cd9 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp @@ -51,7 +51,7 @@ void Ekf::controlFakeHgtFusion() const float obs_var = sq(_params.pos_noaid_noise); const float innov_gate = 3.f; - updateVerticalPositionAidStatus(aid_src, _time_delayed_us, _last_known_pos(2), obs_var, innov_gate); + updateVerticalPositionAidStatus(aid_src, _time_delayed_us, -_last_known_gpos.altitude(), obs_var, innov_gate); const bool continuing_conditions_passing = !isVerticalAidingActive(); const bool starting_conditions_passing = continuing_conditions_passing @@ -98,7 +98,7 @@ void Ekf::controlFakeHgtFusion() void Ekf::resetFakeHgtFusion() { ECL_INFO("reset fake height fusion"); - _last_known_pos(2) = _state.pos(2); + _last_known_gpos.setAltitude(_gpos.altitude()); resetVerticalVelocityToZero(); resetHeightToLastKnown(); @@ -109,8 +109,8 @@ void Ekf::resetFakeHgtFusion() void Ekf::resetHeightToLastKnown() { _information_events.flags.reset_pos_to_last_known = true; - ECL_INFO("reset height to last known (%.3f)", (double)_last_known_pos(2)); - resetVerticalPositionTo(_last_known_pos(2), sq(_params.pos_noaid_noise)); + ECL_INFO("reset height to last known (%.3f)", (double)_last_known_gpos.altitude()); + resetHeightTo(_last_known_gpos.altitude(), sq(_params.pos_noaid_noise)); } void Ekf::stopFakeHgtFusion() diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index ecc6cdfacb90..3e244412ab50 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -63,17 +63,17 @@ void Ekf::controlFakePosFusion() obs_var(0) = obs_var(1) = sq(0.5f); } - const Vector2f position(_last_known_pos); + const Vector2f innovation = (_gpos - _last_known_gpos).xy(); const float innov_gate = 3.f; updateAidSourceStatus(aid_src, _time_delayed_us, - position, // observation - obs_var, // observation variance - Vector2f(_state.pos) - position, // innovation - Vector2f(getStateVariance()) + obs_var, // innovation variance - innov_gate); // innovation gate + Vector2f(_gpos.latitude_deg(), _gpos.longitude_deg()), // observation + obs_var, // observation variance + innovation, // innovation + Vector2f(getStateVariance()) + obs_var, // innovation variance + innov_gate); // innovation gate const bool enable_valid_fake_pos = _control_status.flags.constant_pos || _control_status.flags.vehicle_at_rest; const bool enable_fake_pos = !enable_valid_fake_pos @@ -95,7 +95,7 @@ void Ekf::controlFakePosFusion() void Ekf::resetFakePosFusion() { ECL_INFO("reset fake position fusion"); - _last_known_pos.xy() = _state.pos.xy(); + _last_known_gpos.setLatLon(_gpos); resetHorizontalPositionToLastKnown(); resetHorizontalVelocityToZero(); diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index cc165d453398..78a6d12f90a3 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -62,9 +62,9 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body; const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body; - const float gnss_alt = _gps_sample_delayed.alt + pos_offset_earth(2); + const float gnss_alt = gps_sample.alt + pos_offset_earth(2); - const float measurement = gnss_alt - getEkfGlobalOriginAltitude(); + const float measurement = gnss_alt; const float measurement_var = sq(noise); const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var); @@ -81,13 +81,13 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) if (measurement_valid) { bias_est.setMaxStateNoise(sqrtf(measurement_var)); bias_est.setProcessNoiseSpectralDensity(_params.gps_hgt_bias_nsd); - bias_est.fuseBias(measurement - (-_state.pos(2)), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); + bias_est.fuseBias(measurement - _gpos.altitude(), measurement_var + P(State::pos.idx + 2, State::pos.idx + 2)); } // determine if we should use height aiding const bool continuing_conditions_passing = (_params.gnss_ctrl & static_cast(GnssCtrl::VPOS)) && measurement_valid - && _pos_ref.isInitialized() + && _local_origin_lat_lon.isInitialized() && _gps_checks_passed; const bool starting_conditions_passing = continuing_conditions_passing @@ -105,8 +105,8 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_gps = true; - resetVerticalPositionTo(aid_src.observation, measurement_var); - bias_est.setBias(_state.pos(2) + measurement); + resetHeightTo(measurement, measurement_var); + bias_est.setBias(-_gpos.altitude() + measurement); aid_src.time_last_fuse = _time_delayed_us; @@ -128,13 +128,13 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) _height_sensor_ref = HeightSensor::GNSS; _information_events.flags.reset_hgt_to_gps = true; - resetVerticalPositionTo(-measurement, measurement_var); - _gpos_origin_epv = 0.f; // The uncertainty of the global origin is now contained in the local position uncertainty + + resetAltitudeTo(measurement, measurement_var); bias_est.reset(); } else { ECL_INFO("starting %s height fusion", HGT_SRC_NAME); - bias_est.setBias(_state.pos(2) + measurement); + bias_est.setBias(-_gpos.altitude() + measurement); } aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp index 236fd2dd63e1..c1b47c224fa7 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -57,25 +57,14 @@ void Ekf::collect_gps(const gnssSample &gps) { - if (_filter_initialised && !_pos_ref.isInitialized() && _gps_checks_passed) { - // If we have good GPS data set the origin's WGS-84 position to the last gps fix - setLatLonOriginFromCurrentPos(gps.lat, gps.lon, gps.hacc); - - // Take the current GPS height and subtract the filter height above origin to estimate the GPS height of the origin - if (!PX4_ISFINITE(_gps_alt_ref)) { - setAltOriginFromCurrentPos(gps.alt, gps.vacc); - } - + if (_filter_initialised && !_local_origin_lat_lon.isInitialized() && _gps_checks_passed) { _information_events.flags.gps_checks_passed = true; - ECL_INFO("GPS origin set to lat=%.6f, lon=%.6f", - _pos_ref.getProjectionReferenceLat(), _pos_ref.getProjectionReferenceLon()); - } else { // a rough 2D fix is sufficient to lookup earth spin rate const bool gps_rough_2d_fix = (gps.fix_type >= 2) && (gps.hacc < 1000); - if (gps_rough_2d_fix && (_gps_checks_passed || !_pos_ref.isInitialized())) { + if (gps_rough_2d_fix && (_gps_checks_passed || !_local_origin_lat_lon.isInitialized())) { _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); } } diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index 9799c8bb71d4..de8dad37b5e8 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -82,10 +82,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } } - if (_pos_ref.isInitialized()) { - updateGnssPos(gnss_sample, _aid_src_gnss_pos); - } - + updateGnssPos(gnss_sample, _aid_src_gnss_pos); updateGnssVel(imu_delayed, gnss_sample, _aid_src_gnss_vel); } else if (_control_status.flags.gps) { @@ -108,9 +105,9 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) const bool continuing_conditions_passing = (gnss_vel_enabled || gnss_pos_enabled) && _control_status.flags.tilt_align - && _control_status.flags.yaw_align - && _pos_ref.isInitialized(); + && _control_status.flags.yaw_align; const bool starting_conditions_passing = continuing_conditions_passing && _gps_checks_passed; + const bool gpos_init_conditions_passing = gnss_pos_enabled && _gps_checks_passed; if (_control_status.flags.gps) { if (continuing_conditions_passing) { @@ -174,6 +171,9 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) } _control_status.flags.gps = true; + + } else if (gpos_init_conditions_passing && !_local_origin_lat_lon.isInitialized()) { + resetHorizontalPositionToGnss(_aid_src_gnss_pos); } } } @@ -221,8 +221,10 @@ void Ekf::updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s { // correct position and height for offset relative to IMU const Vector3f pos_offset_body = _params.gps_pos_body - _params.imu_pos_body; - const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body; - const Vector2f position = _pos_ref.project(gnss_sample.lat, gnss_sample.lon) - pos_offset_earth.xy(); + const Vector3f pos_offset_earth = Vector3f(_R_to_earth * pos_offset_body); + const LatLonAlt measurement(gnss_sample.lat, gnss_sample.lon, gnss_sample.alt); + const LatLonAlt measurement_corrected = measurement + (-pos_offset_earth); + const Vector2f innovation = (_gpos - measurement_corrected).xy(); // relax the upper observation noise limit which prevents bad GPS perturbing the position estimate float pos_noise = math::max(gnss_sample.hacc, _params.gps_pos_noise); @@ -237,12 +239,13 @@ void Ekf::updateGnssPos(const gnssSample &gnss_sample, estimator_aid_source2d_s const float pos_var = math::max(sq(pos_noise), sq(0.01f)); const Vector2f pos_obs_var(pos_var, pos_var); + const matrix::Vector2d observation(measurement_corrected.latitude_deg(), measurement_corrected.longitude_deg()); updateAidSourceStatus(aid_src, gnss_sample.time_us, // sample timestamp - position, // observation + observation, // observation pos_obs_var, // observation variance - Vector2f(_state.pos) - position, // innovation + innovation, // innovation Vector2f(getStateVariance()) + pos_obs_var, // innovation variance math::max(_params.gps_pos_innov_gate, 1.f)); // innovation gate } @@ -322,8 +325,9 @@ void Ekf::resetVelocityToGnss(estimator_aid_source3d_s &aid_src) void Ekf::resetHorizontalPositionToGnss(estimator_aid_source2d_s &aid_src) { _information_events.flags.reset_pos_to_gps = true; - resetHorizontalPositionTo(Vector2f(aid_src.observation), Vector2f(aid_src.observation_variance)); - _gpos_origin_eph = 0.f; // The uncertainty of the global origin is now contained in the local position uncertainty + resetLatLonTo(aid_src.observation[0], aid_src.observation[1], + aid_src.observation_variance[0] + + aid_src.observation_variance[1]); resetAidSourceStatusZeroInnovation(aid_src); } diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index cff897d10649..85979a24472e 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -90,12 +90,7 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if (global_origin_valid() && (origin_newer_than_last_mag || (isLocalHorizontalPositionValid() && isTimedOut(_wmm_mag_time_last_checked, 10e6))) ) { - // position of local NED origin in GPS / WGS84 frame - double latitude_deg; - double longitude_deg; - global_origin().reproject(_state.pos(0), _state.pos(1), latitude_deg, longitude_deg); - - if (updateWorldMagneticModel(latitude_deg, longitude_deg)) { + if (updateWorldMagneticModel(_gpos.latitude_deg(), _gpos.longitude_deg())) { wmm_updated = true; } @@ -368,7 +363,7 @@ bool Ekf::checkHaglYawResetReq() const // Check if height has increased sufficiently to be away from ground magnetic anomalies // and request a yaw reset if not already requested. static constexpr float mag_anomalies_max_hagl = 1.5f; - const bool above_mag_anomalies = (getTerrainVPos() - _state.pos(2)) > mag_anomalies_max_hagl; + const bool above_mag_anomalies = (getTerrainVPos() + _gpos.altitude()) > mag_anomalies_max_hagl; return above_mag_anomalies; } diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp index dbbc1a72961b..60238af10572 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp @@ -233,7 +233,9 @@ void Ekf::resetFlowFusion(const flowSample &flow_sample) // reset position, estimate is relative to initial position in this mode, so we start with zero error if (!_control_status.flags.in_air) { ECL_INFO("reset position to zero"); - resetHorizontalPositionTo(Vector2f(0.f, 0.f), 0.f); + //TODO: reset origin instead? + resetHorizontalPositionToLastKnown(); + // resetHorizontalPositionTo(Vector2f(0.f, 0.f), 0.f); } resetAidSourceStatusZeroInnovation(_aid_src_optical_flow); @@ -247,7 +249,7 @@ void Ekf::resetTerrainToFlow() ECL_INFO("reset hagl to flow"); // TODO: use the flow data - const float new_terrain = fmaxf(0.0f, _state.pos(2)); + const float new_terrain = -_gpos.altitude() + _params.rng_gnd_clearance; const float delta_terrain = new_terrain - _state.terrain; _state.terrain = new_terrain; P.uncorrelateCovarianceSetVariance(State::terrain.idx, 100.f); diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp index ea722569d624..747fac96f1b1 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_fusion.cpp @@ -67,7 +67,8 @@ bool Ekf::fuseOptFlow(VectorState &H, const bool update_terrain) // recalculate the innovation using the updated state const Vector3f flow_gyro_corrected = _flow_sample_delayed.gyro_rate - _flow_gyro_bias; - _aid_src_optical_flow.innovation[1] = predictFlow(flow_gyro_corrected)(1) - _aid_src_optical_flow.observation[1]; + _aid_src_optical_flow.innovation[1] = predictFlow(flow_gyro_corrected)(1) - static_cast + (_aid_src_optical_flow.observation[1]); } if (_aid_src_optical_flow.innovation_variance[index] < _aid_src_optical_flow.observation_variance[index]) { diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp index 3a848f7d46cf..2598f3a3318c 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp @@ -148,7 +148,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) _height_sensor_ref = HeightSensor::RANGE; _information_events.flags.reset_hgt_to_rng = true; - resetVerticalPositionTo(-aid_src.observation, aid_src.observation_variance); + resetHeightTo(aid_src.observation, aid_src.observation_variance); _state.terrain = 0.f; _control_status.flags.rng_hgt = true; stopRngTerrFusion(); @@ -180,7 +180,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_rng = true; - resetVerticalPositionTo(-(aid_src.observation - _state.terrain)); + resetHeightTo(aid_src.observation - _state.terrain); // reset vertical velocity if no valid sources available if (!isVerticalVelocityAidingActive()) { diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index f453559c0ef7..e1fb96784fd6 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -74,7 +74,7 @@ void Ekf::reset() // #if defined(CONFIG_EKF2_TERRAIN) // assume a ground clearance - _state.terrain = _state.pos(2) + _params.rng_gnd_clearance; + _state.terrain = -_gpos.altitude() + _params.rng_gnd_clearance; #endif // CONFIG_EKF2_TERRAIN #if defined(CONFIG_EKF2_RANGE_FINDER) @@ -97,7 +97,7 @@ void Ekf::reset() resetGpsDriftCheckFilters(); _gps_checks_passed = false; #endif // CONFIG_EKF2_GNSS - _gps_alt_ref = NAN; + _local_origin_alt = NAN; _output_predictor.reset(); @@ -113,7 +113,7 @@ void Ekf::reset() _time_last_heading_fuse = 0; _time_last_terrain_fuse = 0; - _last_known_pos.setZero(); + _last_known_gpos.setZero(); #if defined(CONFIG_EKF2_BAROMETER) _baro_counter = 0; @@ -168,7 +168,7 @@ bool Ekf::update() // control fusion of observation data controlFusionModes(imu_sample_delayed); - _output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _state.pos, + _output_predictor.correctOutputStates(imu_sample_delayed.time_us, _state.quat_nominal, _state.vel, _gpos, _state.gyro_bias, _state.accel_bias); return true; @@ -205,7 +205,7 @@ bool Ekf::initialiseFilter() initialiseCovariance(); // reset the output predictor state history to match the EKF initial values - _output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _state.pos); + _output_predictor.alignOutputFilter(_state.quat_nominal, _state.vel, _gpos); return true; } @@ -258,11 +258,11 @@ void Ekf::predictState(const imuSample &imu_delayed) _state.vel(2) += CONSTANTS_ONE_G * imu_delayed.delta_vel_dt; // predict position states via trapezoidal integration of velocity - _state.pos += (vel_last + _state.vel) * imu_delayed.delta_vel_dt * 0.5f; + _gpos += (vel_last + _state.vel) * imu_delayed.delta_vel_dt * 0.5f; + _state.pos(2) = -_gpos.altitude(); // constrain states _state.vel = matrix::constrain(_state.vel, -_params.velocity_limit, _params.velocity_limit); - _state.pos = matrix::constrain(_state.pos, -1.e6f, 1.e6f); // calculate a filtered horizontal acceleration with a 1 sec time constant @@ -283,14 +283,12 @@ bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const doubl return false; } - if (!_pos_ref.isInitialized()) { - if (!setLatLonOriginFromCurrentPos(latitude, longitude, eph)) { + if (!_local_origin_lat_lon.isInitialized()) { + if (!resetLatLonTo(latitude, longitude, sq(eph))) { return false; } - if (!PX4_ISFINITE(_gps_alt_ref)) { - setAltOriginFromCurrentPos(altitude, epv); - } + resetAltitudeTo(altitude, sq(epv)); return true; } @@ -315,12 +313,20 @@ bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const doubl pos_correction = _state.vel * dt_s; } - { - const Vector2f hpos = _pos_ref.project(latitude, longitude) + pos_correction.xy(); + LatLonAlt gpos(latitude, longitude, altitude); + bool alt_valid = true; + + if (!checkAltitudeValidity(gpos.altitude())) { + gpos.setAltitude(_gpos.altitude()); + alt_valid = false; + } + + const LatLonAlt gpos_corrected = gpos + pos_correction; + { const float obs_var = math::max(sq(eph), sq(0.01f)); - const Vector2f innov = Vector2f(_state.pos.xy()) - hpos; + const Vector2f innov = (_gpos - gpos_corrected).xy(); const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; const float sq_gate = sq(5.f); // magic hardcoded gate @@ -334,8 +340,8 @@ bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const doubl ECL_INFO("reset position to external observation"); _information_events.flags.reset_pos_to_ext_obs = true; - resetHorizontalPositionTo(hpos, obs_var); - _last_known_pos.xy() = _state.pos.xy(); + resetHorizontalPositionTo(gpos_corrected.latitude_deg(), gpos_corrected.longitude_deg(), obs_var); + _last_known_gpos.setLatLon(gpos_corrected); } else { ECL_INFO("fuse external observation as position measurement"); @@ -348,24 +354,16 @@ bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const doubl _state_reset_status.posNE_change.zero(); _time_last_hor_pos_fuse = _time_delayed_us; - _last_known_pos.xy() = _state.pos.xy(); + _last_known_gpos.setLatLon(gpos_corrected); } } - if (checkAltitudeValidity(altitude)) { - const float altitude_corrected = altitude - pos_correction(2); - - if (!PX4_ISFINITE(_gps_alt_ref)) { - setAltOriginFromCurrentPos(altitude_corrected, epv); + if (alt_valid) { + const float obs_var = math::max(sq(epv), sq(0.01f)); - } else { - const float vpos = -(altitude_corrected - _gps_alt_ref); - const float obs_var = math::max(sq(epv), sq(0.01f)); - - ECL_INFO("reset height to external observation"); - resetVerticalPositionTo(vpos, obs_var); - _last_known_pos(2) = _state.pos(2); - } + ECL_INFO("reset height to external observation"); + resetAltitudeTo(gpos_corrected.altitude(), obs_var); + _last_known_gpos.setAltitude(gpos_corrected.altitude()); } return true; @@ -425,9 +423,10 @@ void Ekf::print_status() (double)getStateVariance()(2) ); + const Vector3f position = getPosition(); printf("Position (%d-%d): [%.3f, %.3f, %.3f] var: [%.1e, %.1e, %.1e]\n", State::pos.idx, State::pos.idx + State::pos.dof - 1, - (double)_state.pos(0), (double)_state.pos(1), (double)_state.pos(2), + (double)position(0), (double)position(1), (double) position(2), (double)getStateVariance()(0), (double)getStateVariance()(1), (double)getStateVariance()(2) ); diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index ec9a00154ff3..a76c0e351782 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -66,6 +66,8 @@ # include "aid_sources/aux_global_position/aux_global_position.hpp" #endif // CONFIG_EKF2_AUX_GLOBAL_POSITION +#include "lat_lon_alt/lat_lon_alt.hpp" + enum class Likelihood { LOW, MEDIUM, HIGH }; class ExternalVisionVel; @@ -102,8 +104,8 @@ class Ekf final : public EstimatorInterface bool isTerrainEstimateValid() const { return _terrain_valid; } // get the estimated terrain vertical position relative to the NED origin - float getTerrainVertPos() const { return _state.terrain; }; - float getHagl() const { return _state.terrain - _state.pos(2); } + float getTerrainVertPos() const { return _state.terrain + getEkfGlobalOriginAltitude(); }; + float getHagl() const { return _state.terrain + _gpos.altitude(); } // get the terrain variance float getTerrainVariance() const { return P(State::terrain.idx, State::terrain.idx); } @@ -192,8 +194,8 @@ class Ekf final : public EstimatorInterface bool checkLatLonValidity(double latitude, double longitude); bool checkAltitudeValidity(float altitude); bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = NAN, float epv = NAN); - bool setEkfGlobalOriginFromCurrentPos(double latitude, double longitude, float altitude, float eph = NAN, - float epv = NAN); + bool resetGlobalPositionTo(double latitude, double longitude, float altitude, float eph = NAN, + float epv = NAN); // get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position void get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const; @@ -217,17 +219,14 @@ class Ekf final : public EstimatorInterface void resetAccelBias(); void resetAccelBiasCov(); - // return true if the global position estimate is valid - // return true if the origin is set we are not doing unconstrained free inertial navigation - // and have not started using synthetic position observations to constrain drift bool isGlobalHorizontalPositionValid() const { - return _pos_ref.isInitialized() && isLocalHorizontalPositionValid(); + return _local_origin_lat_lon.isInitialized() && isLocalHorizontalPositionValid(); } bool isGlobalVerticalPositionValid() const { - return _pos_ref.isInitialized() && isLocalVerticalPositionValid(); + return PX4_ISFINITE(_local_origin_alt) && isLocalVerticalPositionValid(); } bool isLocalHorizontalPositionValid() const @@ -473,6 +472,8 @@ class Ekf final : public EstimatorInterface StateSample _state{}; ///< state struct of the ekf running at the delayed time horizon + LatLonAlt _gpos{0.0, 0.0, 0.f}; + bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised uint64_t _time_last_horizontal_aiding{0}; ///< amount of time we have been doing inertial only deadreckoning (uSec) @@ -486,7 +487,7 @@ class Ekf final : public EstimatorInterface uint64_t _time_last_heading_fuse{0}; uint64_t _time_last_terrain_fuse{0}; - Vector3f _last_known_pos{}; ///< last known local position vector (m) + LatLonAlt _last_known_gpos{}; Vector3f _earth_rate_NED{}; ///< earth rotation vector (NED) in rad/s @@ -645,11 +646,11 @@ class Ekf final : public EstimatorInterface P.slice(S.idx, S.idx) = cov; } - bool setLatLonOrigin(double latitude, double longitude, float eph = NAN); - bool setAltOrigin(float altitude, float epv = NAN); + bool setLatLonOrigin(double latitude, double longitude, float hpos_var = NAN); + bool setAltOrigin(float altitude, float vpos_var = NAN); - bool setLatLonOriginFromCurrentPos(double latitude, double longitude, float eph = NAN); - bool setAltOriginFromCurrentPos(float altitude, float epv = NAN); + bool resetLatLonTo(double latitude, double longitude, float hpos_var = NAN); + bool resetAltitudeTo(float altitude, float vpos_var = NAN); // update quaternion states and covariances using an innovation, observation variance and Jacobian vector bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); @@ -711,14 +712,22 @@ class Ekf final : public EstimatorInterface void resetHorizontalPositionToLastKnown(); - void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var); - void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const float pos_var = NAN) { resetHorizontalPositionTo(new_horz_pos, Vector2f(pos_var, pos_var)); } + void resetHorizontalPositionTo(const double &new_latitude, const double &new_longitude, + const Vector2f &new_horz_pos_var); + void resetHorizontalPositionTo(const double &new_latitude, const double &new_longitude, const float pos_var = NAN) { resetHorizontalPositionTo(new_latitude, new_longitude, Vector2f(pos_var, pos_var)); } + void resetHorizontalPositionTo(const Vector2f &new_pos, const Vector2f &new_horz_pos_var); + + Vector2f getLocalHorizontalPosition() const; + + Vector2f computeDeltaHorizontalPosition(const double &new_latitude, const double &new_longitude) const; + void updateHorizontalPositionResetStatus(const Vector2f &delta); void resetWindTo(const Vector2f &wind, const Vector2f &wind_var); bool isHeightResetRequired() const; - void resetVerticalPositionTo(float new_vert_pos, float new_vert_pos_var = NAN); + void resetHeightTo(float new_altitude, float new_vert_pos_var = NAN); + void updateVerticalPositionResetStatus(const float delta_z); void resetVerticalVelocityToZero(); @@ -740,6 +749,7 @@ class Ekf final : public EstimatorInterface void controlTerrainFakeFusion(); void updateTerrainValidity(); + void updateTerrainResetStatus(const float delta_z); # if defined(CONFIG_EKF2_RANGE_FINDER) // update the terrain vertical position estimate using a height above ground measurement from the range finder @@ -832,6 +842,7 @@ class Ekf final : public EstimatorInterface void startEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, estimator_aid_source2d_s &aid_src); void updateEvPosFusion(const Vector2f &measurement, const Vector2f &measurement_var, bool quality_sufficient, bool reset, estimator_aid_source2d_s &aid_src); + void stopEvPosFusion(); void stopEvHgtFusion(); void stopEvVelFusion(); @@ -1049,9 +1060,9 @@ class Ekf final : public EstimatorInterface } // helper used for populating and filtering estimator aid source struct for logging - template + template void updateAidSourceStatus(T &status, const uint64_t ×tamp_sample, - const S &observation, const S &observation_variance, + const D &observation, const S &observation_variance, const S &innovation, const S &innovation_variance, float innovation_gate = 1.f) const { @@ -1106,7 +1117,7 @@ class Ekf final : public EstimatorInterface status.test_ratio[i] = test_ratio; - status.observation[i] = observation(i); + status.observation[i] = static_cast(observation(i)); status.observation_variance[i] = observation_variance(i); status.innovation[i] = innovation(i); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index d4b3e6031ebd..33e63a6eb64a 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -65,9 +65,9 @@ Vector3f Ekf::calcEarthRateNED(float lat_rad) const void Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const { - origin_time = _pos_ref.getProjectionReferenceTimestamp(); - latitude = _pos_ref.getProjectionReferenceLat(); - longitude = _pos_ref.getProjectionReferenceLon(); + origin_time = _local_origin_lat_lon.getProjectionReferenceTimestamp(); + latitude = _local_origin_lat_lon.getProjectionReferenceLat(); + longitude = _local_origin_lat_lon.getProjectionReferenceLon(); origin_alt = getEkfGlobalOriginAltitude(); } @@ -85,156 +85,170 @@ bool Ekf::checkAltitudeValidity(const float altitude) return (PX4_ISFINITE(altitude) && ((altitude > -12'000.f) && (altitude < 100'000.f))); } -bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph, - const float epv) +bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float hpos_var, + const float vpos_var) { - if (!setLatLonOrigin(latitude, longitude, eph)) { + if (!setLatLonOrigin(latitude, longitude, hpos_var)) { return false; } // altitude is optional - setAltOrigin(altitude, epv); + setAltOrigin(altitude, vpos_var); return true; } -bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const float eph) +bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const float hpos_var) { if (!checkLatLonValidity(latitude, longitude)) { return false; } - bool current_pos_available = false; - double current_lat = static_cast(NAN); - double current_lon = static_cast(NAN); + if (!_local_origin_lat_lon.isInitialized() && isLocalHorizontalPositionValid()) { + // Already navigating in a local frame, use the origin to initialize global position + const Vector2f pos_prev = getLocalHorizontalPosition(); + _local_origin_lat_lon.initReference(latitude, longitude, _time_delayed_us); + double new_latitude; + double new_longitude; + _local_origin_lat_lon.reproject(pos_prev(0), pos_prev(1), new_latitude, new_longitude); + resetHorizontalPositionTo(new_latitude, new_longitude, hpos_var); - // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (_pos_ref.isInitialized() && isLocalHorizontalPositionValid()) { - _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); - current_pos_available = true; - } - - // reinitialize map projection to latitude, longitude, altitude, and reset position - _pos_ref.initReference(latitude, longitude, _time_delayed_us); - - if (PX4_ISFINITE(eph) && (eph >= 0.f)) { - _gpos_origin_eph = eph; - } - - if (current_pos_available) { - // reset horizontal position if we already have a global origin - Vector2f position = _pos_ref.project(current_lat, current_lon); - resetHorizontalPositionTo(position); + } else { + // Simply move the origin and compute the change in local position + const Vector2f pos_prev = getLocalHorizontalPosition(); + _local_origin_lat_lon.initReference(latitude, longitude, _time_delayed_us); + const Vector2f pos_new = getLocalHorizontalPosition(); + const Vector2f delta_pos = pos_new - pos_prev; + updateHorizontalPositionResetStatus(delta_pos); } return true; } -bool Ekf::setAltOrigin(const float altitude, const float epv) +bool Ekf::setAltOrigin(const float altitude, const float vpos_var) { if (!checkAltitudeValidity(altitude)) { return false; } - const float gps_alt_ref_prev = _gps_alt_ref; - _gps_alt_ref = altitude; + ECL_INFO("EKF origin altitude %.1fm -> %.1fm", (double)_local_origin_alt, + (double)altitude); - if (PX4_ISFINITE(epv) && (epv >= 0.f)) { - _gpos_origin_epv = epv; - } + if (!PX4_ISFINITE(_local_origin_alt) && isLocalVerticalPositionValid()) { + const float local_alt_prev = _gpos.altitude(); + _local_origin_alt = altitude; + resetHeightTo(local_alt_prev + _local_origin_alt); - if (PX4_ISFINITE(gps_alt_ref_prev) && isLocalVerticalPositionValid()) { - // determine current z - const float z_prev = _state.pos(2); - const float current_alt = -z_prev + gps_alt_ref_prev; -#if defined(CONFIG_EKF2_GNSS) - const float gps_hgt_bias = _gps_hgt_b_est.getBias(); -#endif // CONFIG_EKF2_GNSS - resetVerticalPositionTo(_gps_alt_ref - current_alt); - ECL_DEBUG("EKF global origin updated, resetting vertical position %.1fm -> %.1fm", (double)z_prev, - (double)_state.pos(2)); -#if defined(CONFIG_EKF2_GNSS) - // adjust existing GPS height bias - _gps_hgt_b_est.setBias(gps_hgt_bias); -#endif // CONFIG_EKF2_GNSS + } else { + const float delta_origin_alt = altitude - _local_origin_alt; + _local_origin_alt = altitude; + updateVerticalPositionResetStatus(-delta_origin_alt); + +#if defined(CONFIG_EKF2_TERRAIN) + updateTerrainResetStatus(-delta_origin_alt); +#endif // CONFIG_EKF2_TERRAIN } return true; } -bool Ekf::setEkfGlobalOriginFromCurrentPos(const double latitude, const double longitude, const float altitude, - const float eph, const float epv) +bool Ekf::resetGlobalPositionTo(const double latitude, const double longitude, const float altitude, + const float hpos_var, const float vpos_var) { - if (!setLatLonOriginFromCurrentPos(latitude, longitude, eph)) { + if (!resetLatLonTo(latitude, longitude, hpos_var)) { return false; } // altitude is optional - setAltOriginFromCurrentPos(altitude, epv); + resetAltitudeTo(altitude, vpos_var); return true; } -bool Ekf::setLatLonOriginFromCurrentPos(const double latitude, const double longitude, const float eph) +bool Ekf::resetLatLonTo(const double latitude, const double longitude, const float hpos_var) { if (!checkLatLonValidity(latitude, longitude)) { return false; } - _pos_ref.initReference(latitude, longitude, _time_delayed_us); + Vector2f pos_prev; + + if (!_local_origin_lat_lon.isInitialized()) { + MapProjection zero_ref; + zero_ref.initReference(0.0, 0.0); + pos_prev = zero_ref.project(_gpos.latitude_deg(), _gpos.longitude_deg()); + + _local_origin_lat_lon.initReference(latitude, longitude, _time_delayed_us); + + // if we are already doing aiding, correct for the change in position since the EKF started navigating + if (isLocalHorizontalPositionValid()) { + double est_lat; + double est_lon; + _local_origin_lat_lon.reproject(-pos_prev(0), -pos_prev(1), est_lat, est_lon); + _local_origin_lat_lon.initReference(est_lat, est_lon, _time_delayed_us); + } + + ECL_INFO("Origin set to lat=%.6f, lon=%.6f", + _local_origin_lat_lon.getProjectionReferenceLat(), _local_origin_lat_lon.getProjectionReferenceLon()); - // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (isLocalHorizontalPositionValid()) { - double est_lat; - double est_lon; - _pos_ref.reproject(-_state.pos(0), -_state.pos(1), est_lat, est_lon); - _pos_ref.initReference(est_lat, est_lon, _time_delayed_us); + } else { + pos_prev = _local_origin_lat_lon.project(_gpos.latitude_deg(), _gpos.longitude_deg()); } - if (PX4_ISFINITE(eph) && (eph >= 0.f)) { - _gpos_origin_eph = eph; + _gpos.setLatLonDeg(latitude, longitude); + _output_predictor.resetLatLonTo(latitude, longitude); + + const Vector2f delta_horz_pos = getLocalHorizontalPosition() - pos_prev; + +#if defined(CONFIG_EKF2_EXTERNAL_VISION) + _ev_pos_b_est.setBias(_ev_pos_b_est.getBias() - delta_horz_pos); +#endif // CONFIG_EKF2_EXTERNAL_VISION + + updateHorizontalPositionResetStatus(delta_horz_pos); + + if (PX4_ISFINITE(hpos_var)) { + P.uncorrelateCovarianceSetVariance<2>(State::pos.idx, math::max(sq(0.01f), hpos_var)); } + // Reset the timout timer + _time_last_hor_pos_fuse = _time_delayed_us; + return true; } -bool Ekf::setAltOriginFromCurrentPos(const float altitude, const float epv) +bool Ekf::resetAltitudeTo(const float altitude, const float vpos_var) { if (!checkAltitudeValidity(altitude)) { return false; } - _gps_alt_ref = altitude + _state.pos(2); + if (!PX4_ISFINITE(_local_origin_alt)) { + const float local_alt_prev = _gpos.altitude(); - if (PX4_ISFINITE(epv) && (epv >= 0.f)) { - _gpos_origin_epv = epv; + if (isLocalVerticalPositionValid()) { + _local_origin_alt = altitude - local_alt_prev; + + } else { + _local_origin_alt = altitude; + } + + ECL_INFO("Origin alt=%.3f", (double)_local_origin_alt); } + resetHeightTo(altitude, vpos_var); + return true; } void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const { - float eph = INFINITY; - float epv = INFINITY; - if (global_origin_valid()) { - // report absolute accuracy taking into account the uncertainty in location of the origin - eph = sqrtf(P.trace<2>(State::pos.idx + 0) + sq(_gpos_origin_eph)); - epv = sqrtf(P.trace<1>(State::pos.idx + 2) + sq(_gpos_origin_epv)); - - if (_horizontal_deadreckon_time_exceeded) { - float lpos_eph = 0.f; - float lpos_epv = 0.f; - get_ekf_lpos_accuracy(&lpos_eph, &lpos_epv); + get_ekf_lpos_accuracy(ekf_eph, ekf_epv); - eph = math::max(eph, lpos_eph); - epv = math::max(epv, lpos_epv); - } + } else { + *ekf_eph = INFINITY; + *ekf_epv = INFINITY; } - - *ekf_eph = eph; - *ekf_epv = epv; } void Ekf::get_ekf_lpos_accuracy(float *ekf_eph, float *ekf_epv) const @@ -726,7 +740,13 @@ void Ekf::fuse(const VectorState &K, float innovation) _state.vel = matrix::constrain(_state.vel - K.slice(State::vel.idx, 0) * innovation, -1.e3f, 1.e3f); // pos - _state.pos = matrix::constrain(_state.pos - K.slice(State::pos.idx, 0) * innovation, -1.e6f, 1.e6f); + const Vector3f pos_correction = K.slice(State::pos.idx, 0) * (-innovation); + + // Accumulate position in global coordinates + _gpos += pos_correction; + _state.pos.zero(); + // Also store altitude in the state vector as this is used for optical flow fusion + _state.pos(2) = -_gpos.altitude(); // gyro_bias _state.gyro_bias = matrix::constrain(_state.gyro_bias - K.slice(State::gyro_bias.idx, diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index a188d2f88e30..5322fe09976c 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -42,6 +42,7 @@ #ifndef EKF_ESTIMATOR_INTERFACE_H #define EKF_ESTIMATOR_INTERFACE_H +#include "lat_lon_alt/lat_lon_alt.hpp" #if defined(MODULE_NAME) #include # define ECL_INFO PX4_DEBUG @@ -241,7 +242,26 @@ class EstimatorInterface Vector3f getVelocity() const { return _output_predictor.getVelocity(); } const Vector3f &getVelocityDerivative() const { return _output_predictor.getVelocityDerivative(); } float getVerticalPositionDerivative() const { return _output_predictor.getVerticalPositionDerivative(); } - Vector3f getPosition() const { return _output_predictor.getPosition(); } + Vector3f getPosition() const + { + LatLonAlt lla = _output_predictor.getLatLonAlt(); + float x; + float y; + + if (_local_origin_lat_lon.isInitialized()) { + _local_origin_lat_lon.project(lla.latitude_deg(), lla.longitude_deg(), x, y); + + } else { + MapProjection zero_ref; + zero_ref.initReference(0.0, 0.0); + zero_ref.project(lla.latitude_deg(), lla.longitude_deg(), x, y); + } + + const float z = -(lla.altitude() - getEkfGlobalOriginAltitude()); + + return Vector3f(x, y, z); + } + LatLonAlt getLatLonAlt() const { return _output_predictor.getLatLonAlt(); } const Vector3f &getOutputTrackingError() const { return _output_predictor.getOutputTrackingError(); } #if defined(CONFIG_EKF2_MAGNETOMETER) @@ -307,9 +327,9 @@ class EstimatorInterface const imuSample &get_imu_sample_delayed() const { return _imu_buffer.get_oldest(); } const uint64_t &time_delayed_us() const { return _time_delayed_us; } - bool global_origin_valid() const { return _pos_ref.isInitialized(); } - const MapProjection &global_origin() const { return _pos_ref; } - float getEkfGlobalOriginAltitude() const { return PX4_ISFINITE(_gps_alt_ref) ? _gps_alt_ref : 0.f; } + bool global_origin_valid() const { return _local_origin_lat_lon.isInitialized(); } + const MapProjection &global_origin() const { return _local_origin_lat_lon; } + float getEkfGlobalOriginAltitude() const { return PX4_ISFINITE(_local_origin_alt) ? _local_origin_alt : 0.f; } OutputPredictor &output_predictor() { return _output_predictor; }; @@ -379,10 +399,8 @@ class EstimatorInterface bool _initialised{false}; // true if the ekf interface instance (data buffering) is initialized // Variables used to publish the WGS-84 location of the EKF local NED origin - MapProjection _pos_ref{}; // Contains WGS-84 position latitude and longitude of the EKF origin - float _gps_alt_ref{NAN}; ///< WGS-84 height (m) - float _gpos_origin_eph{0.0f}; // horizontal position uncertainty of the global origin - float _gpos_origin_epv{0.0f}; // vertical position uncertainty of the global origin + MapProjection _local_origin_lat_lon{}; + float _local_origin_alt{NAN}; #if defined(CONFIG_EKF2_GNSS) RingBuffer *_gps_buffer {nullptr}; diff --git a/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt b/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt new file mode 100644 index 000000000000..bf2b3ebf536b --- /dev/null +++ b/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt @@ -0,0 +1 @@ +px4_add_unit_gtest(SRC test_lat_lon_alt.cpp LINKLIBS geo) diff --git a/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp new file mode 100644 index 000000000000..0fa7115df77a --- /dev/null +++ b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp @@ -0,0 +1,154 @@ +/**************************************************************************** + * + * Copyright (c) 2024 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. + * + ****************************************************************************/ + +#pragma once + +#include "mathlib/math/Limits.hpp" +#include + +class LatLonAlt +{ +public: + LatLonAlt() = default; + LatLonAlt(const LatLonAlt &lla) + { + _latitude_rad = lla.latitude_rad(); + _longitude_rad = lla.longitude_rad(); + _altitude = lla.altitude(); + } + + LatLonAlt(const double latitude_deg, const double longitude_deg, const float altitude_m) + { + _latitude_rad = math::radians(latitude_deg); + _longitude_rad = math::radians(longitude_deg); + _altitude = altitude_m; + } + + void setZero() { _latitude_rad = 0.0; _longitude_rad = 0.0; _altitude = 0.f; } + + double latitude_deg() const { return math::degrees(latitude_rad()); } + double longitude_deg() const { return math::degrees(longitude_rad()); } + + const double &latitude_rad() const { return _latitude_rad; } + const double &longitude_rad() const { return _longitude_rad; } + float altitude() const { return _altitude; } + + void setLatitudeDeg(const double &latitude_deg) { _latitude_rad = math::radians(latitude_deg); } + void setLongitudeDeg(const double &longitude_deg) { _longitude_rad = math::radians(longitude_deg); } + void setAltitude(const float altitude) { _altitude = altitude; } + + void setLatLon(const LatLonAlt &lla) { _latitude_rad = lla.latitude_rad(); _longitude_rad = lla.longitude_rad(); } + void setLatLonDeg(const double latitude, const double longitude) { _latitude_rad = math::radians(latitude); _longitude_rad = math::radians(longitude); } + void setLatLonRad(const double latitude, const double longitude) { _latitude_rad = latitude; _longitude_rad = longitude; } + + void print() const { printf("latitude = %f (deg), longitude = %f (deg), altitude = %f (m)\n", _latitude_rad, _longitude_rad, (double)_altitude); } + + void operator+=(const matrix::Vector3f &delta_pos) + { + matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); + _latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); + _longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); + _altitude -= delta_pos(2); + } + + void operator+=(const matrix::Vector2f &delta_pos) + { + matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); + _latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); + _longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); + } + + LatLonAlt operator+(const matrix::Vector3f &delta_pos) const + { + matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(latitude_rad(), altitude()); + const double latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); + const double longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); + const float altitude = _altitude - delta_pos(2); + + LatLonAlt lla_new; + lla_new.setLatLonRad(latitude_rad, longitude_rad); + lla_new.setAltitude(altitude); + return lla_new; + } + + void operator=(const LatLonAlt &lla) + { + _latitude_rad = lla.latitude_rad(); + _longitude_rad = lla.longitude_rad(); + _altitude = lla.altitude(); + } + + matrix::Vector3f operator-(const LatLonAlt &lla) const + { + const double delta_lat = matrix::wrap_pi(_latitude_rad - lla.latitude_rad()); + const double delta_lon = matrix::wrap_pi(_longitude_rad - lla.longitude_rad()); + const float delta_alt = _altitude - lla.altitude(); + + const matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); + return matrix::Vector3f(static_cast(delta_lat * d_lat_lon_to_d_xy(0)), + static_cast(delta_lon * d_lat_lon_to_d_xy(1)), + -delta_alt); + } + +private: + // Convert between curvilinear and cartesian errors + static matrix::Vector2d deltaLatLonToDeltaXY(const double latitude, const float altitude) + { + double r_n; + double r_e; + computeRadiiOfCurvature(latitude, r_n, r_e); + const double dn_dlat = r_n + static_cast(altitude); + const double de_dlon = (r_e + static_cast(altitude)) * cos(latitude); + + return matrix::Vector2d(dn_dlat, de_dlon); + } + + static void computeRadiiOfCurvature(const double latitude, double &meridian_radius_of_curvature, + double &transverse_radius_of_curvature) + { + const double tmp = 1.0 - pow(Wgs84::eccentricity * sin(latitude), 2); + const double sqrt_tmp = std::sqrt(tmp); + meridian_radius_of_curvature = Wgs84::meridian_radius_of_curvature_numerator / (tmp * tmp * sqrt_tmp); + transverse_radius_of_curvature = Wgs84::equatorial_radius / sqrt_tmp; + } + + struct Wgs84 { + static constexpr double equatorial_radius = 6378137.0; + static constexpr double eccentricity = 0.0818191908425; + static constexpr double meridian_radius_of_curvature_numerator = equatorial_radius * (1.0 - eccentricity *eccentricity); + }; + + double _latitude_rad{0.0}; + double _longitude_rad{0.0}; + float _altitude{0.0}; +}; diff --git a/src/modules/ekf2/EKF/lat_lon_alt/test_lat_lon_alt.cpp b/src/modules/ekf2/EKF/lat_lon_alt/test_lat_lon_alt.cpp new file mode 100644 index 000000000000..b7a42ebd48d3 --- /dev/null +++ b/src/modules/ekf2/EKF/lat_lon_alt/test_lat_lon_alt.cpp @@ -0,0 +1,107 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include + +#include "lat_lon_alt.hpp" + +using namespace matrix; +using math::radians; +using math::degrees; + +TEST(TestLatLonAlt, init) +{ + LatLonAlt lla(5.7, -2.3, 420); + ASSERT_FLOAT_EQ(lla.latitude_deg(), 5.7); + ASSERT_FLOAT_EQ(lla.longitude_deg(), -2.3); + ASSERT_EQ(lla.altitude(), 420); +} + +TEST(TestLatLonAlt, set) +{ + LatLonAlt lla(0.0, 0.0, 0); + ASSERT_EQ(lla.latitude_rad(), 0.0); + ASSERT_EQ(lla.longitude_rad(), 0.0); + ASSERT_EQ(lla.altitude(), 0); + + lla.setLatLonRad(0.1, -0.5); + lla.setAltitude(420); + ASSERT_EQ(lla.latitude_rad(), 0.1); + ASSERT_EQ(lla.longitude_rad(), -0.5); + ASSERT_EQ(lla.altitude(), 420); +} + +TEST(TestLatLonAlt, copy) +{ + LatLonAlt lla(-0.8, -0.1, 500); + + LatLonAlt lla_copy = lla; + ASSERT_EQ(lla_copy.latitude_deg(), -0.8); + ASSERT_EQ(lla_copy.longitude_deg(), -0.1); + ASSERT_EQ(lla_copy.altitude(), 500); +} + +TEST(TestLatLonAlt, addDeltaPos) +{ + MapProjection pos_ref(60.0, 5.0); + LatLonAlt lla(pos_ref.getProjectionReferenceLat(), pos_ref.getProjectionReferenceLon(), 400.f); + + Vector3f delta_pos(5.f, -2.f, 3.f); + lla += delta_pos; + + double lat_new, lon_new; + pos_ref.reproject(delta_pos(0), delta_pos(1), lat_new, lon_new); + + EXPECT_NEAR(lla.latitude_deg(), lat_new, 1e-6); + EXPECT_NEAR(lla.longitude_deg(), lon_new, 1e-6); + EXPECT_EQ(lla.altitude(), 397.f); +} + +TEST(TestLatLonAlt, subLatLonAlt) +{ + MapProjection pos_ref(60.0, 5.0); + LatLonAlt lla(pos_ref.getProjectionReferenceLat(), pos_ref.getProjectionReferenceLon(), 0.f); + + const Vector3f delta_pos_true(1.f, -2.f, 3.f); + + double lat_new, lon_new; + pos_ref.reproject(delta_pos_true(0), delta_pos_true(1), lat_new, lon_new); + LatLonAlt lla_new(lat_new, lon_new, -3.f); + Vector3f delta_pos = lla_new - lla; + + EXPECT_NEAR(delta_pos(0), delta_pos_true(0), 1e-2); + EXPECT_NEAR(delta_pos(1), delta_pos_true(1), 1e-2); + EXPECT_EQ(delta_pos(2), delta_pos_true(2)); +} diff --git a/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp index d16e20a79095..5657d68a2029 100644 --- a/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.cpp @@ -69,7 +69,7 @@ void OutputPredictor::print_status() _output_vert_buffer.entries(), _output_vert_buffer.get_length(), _output_vert_buffer.get_total_size()); } -void OutputPredictor::alignOutputFilter(const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state) +void OutputPredictor::alignOutputFilter(const Quatf &quat_state, const Vector3f &vel_state, const LatLonAlt &gpos_state) { const outputSample &output_delayed = _output_buffer.get_oldest(); @@ -77,9 +77,12 @@ void OutputPredictor::alignOutputFilter(const Quatf &quat_state, const Vector3f Quatf q_delta{quat_state * output_delayed.quat_nominal.inversed()}; q_delta.normalize(); - // calculate the velocity and position deltas between the output and EKF at the EKF fusion time horizon + // calculate the velocity delta between the output and EKF at the EKF fusion time horizon const Vector3f vel_delta = vel_state - output_delayed.vel; - const Vector3f pos_delta = pos_state - output_delayed.pos; + + // zero the position error at delayed time and reset the global reference + const Vector3f pos_delta = -output_delayed.pos; + _global_ref = gpos_state; // loop through the output filter state history and add the deltas for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { @@ -156,29 +159,15 @@ void OutputPredictor::resetVerticalVelocityTo(float delta_vert_vel) _output_vert_new.vert_vel += delta_vert_vel; } -void OutputPredictor::resetHorizontalPositionTo(const Vector2f &delta_horz_pos) +void OutputPredictor::resetLatLonTo(const double &new_latitude, const double &new_longitude) { - for (uint8_t index = 0; index < _output_buffer.get_length(); index++) { - _output_buffer[index].pos.xy() += delta_horz_pos; - } - - _output_new.pos.xy() += delta_horz_pos; + _global_ref.setLatitudeDeg(new_latitude); + _global_ref.setLongitudeDeg(new_longitude); } -void OutputPredictor::resetVerticalPositionTo(const float new_vert_pos, const float vert_pos_change) +void OutputPredictor::resetAltitudeTo(const float new_altitude, const float vert_pos_change) { - // apply the change in height / height rate to our newest height / height rate estimate - // which have already been taken out from the output buffer - _output_new.pos(2) += vert_pos_change; - - // add the reset amount to the output observer buffered data - for (uint8_t i = 0; i < _output_buffer.get_length(); i++) { - _output_buffer[i].pos(2) += vert_pos_change; - _output_vert_buffer[i].vert_vel_integ += vert_pos_change; - } - - // add the reset amount to the output observer vertical position state - _output_vert_new.vert_vel_integ = new_vert_pos; + _global_ref.setAltitude(new_altitude); } void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector3f &delta_angle, @@ -261,7 +250,7 @@ void OutputPredictor::calculateOutputStates(const uint64_t time_us, const Vector } void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, - const Quatf &quat_state, const Vector3f &vel_state, const Vector3f &pos_state, const matrix::Vector3f &gyro_bias, + const Quatf &quat_state, const Vector3f &vel_state, const LatLonAlt &gpos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias) { // calculate an average filter update time @@ -317,6 +306,8 @@ void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, const float vel_gain = _dt_correct_states_avg / math::constrain(_vel_tau, _dt_correct_states_avg, 10.f); const float pos_gain = _dt_correct_states_avg / math::constrain(_pos_tau, _dt_correct_states_avg, 10.f); + const Vector3f pos_state = gpos_state - _global_ref; + // calculate down velocity and position tracking errors const float vert_vel_err = (vel_state(2) - output_vert_delayed.vert_vel); const float vert_vel_integ_err = (pos_state(2) - output_vert_delayed.vert_vel_integ); @@ -325,7 +316,7 @@ void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, // using a PD feedback tuned to a 5% overshoot const float vert_vel_correction = vert_vel_integ_err * pos_gain + vert_vel_err * vel_gain * 1.1f; - applyCorrectionToVerticalOutputBuffer(vert_vel_correction); + applyCorrectionToVerticalOutputBuffer(vert_vel_correction, pos_state(2)); // calculate velocity and position tracking errors const Vector3f vel_err(vel_state - output_delayed.vel); @@ -342,10 +333,14 @@ void OutputPredictor::correctOutputStates(const uint64_t time_delayed_us, _pos_err_integ += pos_err; const Vector3f pos_correction = pos_err * pos_gain + _pos_err_integ * sq(pos_gain) * 0.1f; - applyCorrectionToOutputBuffer(vel_correction, pos_correction); + // as the reference changes, adjust the position correction to keep a constant global position + const Vector3f pos_correction_with_ref_change = pos_correction - pos_state; + applyCorrectionToOutputBuffer(vel_correction, pos_correction_with_ref_change); + + _global_ref = gpos_state; } -void OutputPredictor::applyCorrectionToVerticalOutputBuffer(float vert_vel_correction) +void OutputPredictor::applyCorrectionToVerticalOutputBuffer(const float vert_vel_correction, const float pos_ref_change) { // loop through the vertical output filter state history starting at the oldest and apply the corrections to the // vert_vel states and propagate vert_vel_integ forward using the corrected vert_vel @@ -367,7 +362,7 @@ void OutputPredictor::applyCorrectionToVerticalOutputBuffer(float vert_vel_corre // position is propagated forward using the corrected velocity and a trapezoidal integrator next_state.vert_vel_integ = current_state.vert_vel_integ + (current_state.vert_vel + next_state.vert_vel) * 0.5f * - next_state.dt; + next_state.dt - pos_ref_change; // advance the index index = (index + 1) % size; diff --git a/src/modules/ekf2/EKF/output_predictor/output_predictor.h b/src/modules/ekf2/EKF/output_predictor/output_predictor.h index 07248f3dce72..33b7f127bc05 100644 --- a/src/modules/ekf2/EKF/output_predictor/output_predictor.h +++ b/src/modules/ekf2/EKF/output_predictor/output_predictor.h @@ -37,6 +37,7 @@ #include #include "../RingBuffer.h" +#include "../lat_lon_alt/lat_lon_alt.hpp" #include @@ -52,7 +53,7 @@ class OutputPredictor // modify output filter to match the the EKF state at the fusion time horizon void alignOutputFilter(const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, - const matrix::Vector3f &pos_state); + const LatLonAlt &gpos_state); /* * Implement a strapdown INS algorithm using the latest IMU data at the current time horizon. * Buffer the INS states and calculate the difference with the EKF states at the delayed fusion time horizon. @@ -67,7 +68,7 @@ class OutputPredictor const matrix::Vector3f &delta_velocity, const float delta_velocity_dt); void correctOutputStates(const uint64_t time_delayed_us, - const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const matrix::Vector3f &pos_state, + const matrix::Quatf &quat_state, const matrix::Vector3f &vel_state, const LatLonAlt &gpos_state, const matrix::Vector3f &gyro_bias, const matrix::Vector3f &accel_bias); void resetQuaternion(const matrix::Quatf &quat_change); @@ -75,8 +76,8 @@ class OutputPredictor void resetHorizontalVelocityTo(const matrix::Vector2f &delta_horz_vel); void resetVerticalVelocityTo(float delta_vert_vel); - void resetHorizontalPositionTo(const matrix::Vector2f &delta_horz_pos); - void resetVerticalPositionTo(const float new_vert_pos, const float vert_pos_change); + void resetLatLonTo(const double &new_latitude, const double &new_longitude); + void resetAltitudeTo(float new_altitude, float vert_pos_change); void print_status(); @@ -106,13 +107,12 @@ class OutputPredictor // get the derivative of the vertical position of the body frame origin in local NED earth frame float getVerticalPositionDerivative() const { return _output_vert_new.vert_vel - _vel_imu_rel_body_ned(2); } - // get the position of the body frame origin in local earth frame - matrix::Vector3f getPosition() const + LatLonAlt getLatLonAlt() const { // rotate the position of the IMU relative to the boy origin into earth frame const matrix::Vector3f pos_offset_earth{_R_to_earth_now * _imu_pos_body}; // subtract from the EKF position (which is at the IMU) to get position at the body origin - return _output_new.pos - pos_offset_earth; + return _global_ref + (_output_new.pos - pos_offset_earth); } // return an array containing the output predictor angular, velocity and position tracking @@ -133,7 +133,7 @@ class OutputPredictor * This provides an alternative vertical velocity output that is closer to the first derivative * of the position but does degrade tracking relative to the EKF state. */ - void applyCorrectionToVerticalOutputBuffer(float vert_vel_correction); + void applyCorrectionToVerticalOutputBuffer(float vert_vel_correction, const float pos_ref_change); /* * Calculate corrections to be applied to vel and pos output state history. @@ -159,6 +159,8 @@ class OutputPredictor float dt{0.f}; ///< delta time (sec) }; + LatLonAlt _global_ref{0.0, 0.0, 0.f}; + RingBuffer _output_buffer{12}; RingBuffer _output_vert_buffer{12}; diff --git a/src/modules/ekf2/EKF/position_fusion.cpp b/src/modules/ekf2/EKF/position_fusion.cpp index 90080458423b..e4c16b49415b 100644 --- a/src/modules/ekf2/EKF/position_fusion.cpp +++ b/src/modules/ekf2/EKF/position_fusion.cpp @@ -36,7 +36,7 @@ void Ekf::updateVerticalPositionAidStatus(estimator_aid_source1d_s &aid_src, const uint64_t &time_us, const float observation, const float observation_variance, const float innovation_gate) const { - float innovation = _state.pos(2) - observation; + float innovation = -_gpos.altitude() - observation; float innovation_variance = getStateVariance()(2) + observation_variance; updateAidSourceStatus(aid_src, time_us, @@ -93,10 +93,20 @@ bool Ekf::fuseVerticalPosition(estimator_aid_source1d_s &aid_src) return aid_src.fused; } -void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var) +void Ekf::resetHorizontalPositionTo(const double &new_latitude, const double &new_longitude, + const Vector2f &new_horz_pos_var) { - const Vector2f delta_horz_pos{new_horz_pos - Vector2f{_state.pos}}; - _state.pos.xy() = new_horz_pos; + const Vector2f delta_horz_pos = computeDeltaHorizontalPosition(new_latitude, new_longitude); + + updateHorizontalPositionResetStatus(delta_horz_pos); + +#if defined(CONFIG_EKF2_EXTERNAL_VISION) + _ev_pos_b_est.setBias(_ev_pos_b_est.getBias() - delta_horz_pos); +#endif // CONFIG_EKF2_EXTERNAL_VISION + //_gps_pos_b_est.setBias(_gps_pos_b_est.getBias() + _state_reset_status.posNE_change); + + _gpos.setLatLonDeg(new_latitude, new_longitude); + _output_predictor.resetLatLonTo(new_latitude, new_longitude); if (PX4_ISFINITE(new_horz_pos_var(0))) { P.uncorrelateCovarianceSetVariance<1>(State::pos.idx, math::max(sq(0.01f), new_horz_pos_var(0))); @@ -106,54 +116,89 @@ void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f P.uncorrelateCovarianceSetVariance<1>(State::pos.idx + 1, math::max(sq(0.01f), new_horz_pos_var(1))); } - _output_predictor.resetHorizontalPositionTo(delta_horz_pos); + // Reset the timout timer + _time_last_hor_pos_fuse = _time_delayed_us; +} + +Vector2f Ekf::computeDeltaHorizontalPosition(const double &new_latitude, const double &new_longitude) const +{ + Vector2f pos; + Vector2f pos_new; + + if (_local_origin_lat_lon.isInitialized()) { + _local_origin_lat_lon.project(_gpos.latitude_deg(), _gpos.longitude_deg(), pos(0), pos(1)); + _local_origin_lat_lon.project(new_latitude, new_longitude, pos_new(0), pos_new(1)); + + } else { + MapProjection zero_ref; + zero_ref.initReference(0.0, 0.0); + zero_ref.project(_gpos.latitude_deg(), _gpos.longitude_deg(), pos(0), pos(1)); + zero_ref.project(new_latitude, new_longitude, pos_new(0), pos_new(1)); + } + + return pos_new - pos; +} - // record the state change +Vector2f Ekf::getLocalHorizontalPosition() const +{ + if (_local_origin_lat_lon.isInitialized()) { + return _local_origin_lat_lon.project(_gpos.latitude_deg(), _gpos.longitude_deg()); + + } else { + MapProjection zero_ref; + zero_ref.initReference(0.0, 0.0); + return zero_ref.project(_gpos.latitude_deg(), _gpos.longitude_deg()); + } +} + +void Ekf::updateHorizontalPositionResetStatus(const Vector2f &delta) +{ if (_state_reset_status.reset_count.posNE == _state_reset_count_prev.posNE) { - _state_reset_status.posNE_change = delta_horz_pos; + _state_reset_status.posNE_change = delta; } else { // there's already a reset this update, accumulate total delta - _state_reset_status.posNE_change += delta_horz_pos; + _state_reset_status.posNE_change += delta; } _state_reset_status.reset_count.posNE++; +} -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - _ev_pos_b_est.setBias(_ev_pos_b_est.getBias() - _state_reset_status.posNE_change); -#endif // CONFIG_EKF2_EXTERNAL_VISION - //_gps_pos_b_est.setBias(_gps_pos_b_est.getBias() + _state_reset_status.posNE_change); +void Ekf::resetHorizontalPositionTo(const Vector2f &new_pos, + const Vector2f &new_horz_pos_var) +{ + double new_latitude; + double new_longitude; - // Reset the timout timer - _time_last_hor_pos_fuse = _time_delayed_us; + if (_local_origin_lat_lon.isInitialized()) { + _local_origin_lat_lon.reproject(new_pos(0), new_pos(1), new_latitude, new_longitude); + + } else { + MapProjection zero_ref; + zero_ref.initReference(0.0, 0.0); + zero_ref.reproject(new_pos(0), new_pos(1), new_latitude, new_longitude); + } + + resetHorizontalPositionTo(new_latitude, new_longitude, new_horz_pos_var); } -void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_var) +void Ekf::resetHeightTo(const float new_altitude, float new_vert_pos_var) { - const float old_vert_pos = _state.pos(2); - _state.pos(2) = new_vert_pos; + const float old_altitude = _gpos.altitude(); + _gpos.setAltitude(new_altitude); if (PX4_ISFINITE(new_vert_pos_var)) { // the state variance is the same as the observation P.uncorrelateCovarianceSetVariance<1>(State::pos.idx + 2, math::max(sq(0.01f), new_vert_pos_var)); } - const float delta_z = new_vert_pos - old_vert_pos; + const float delta_z = -(new_altitude - old_altitude); // apply the change in height / height rate to our newest height / height rate estimate // which have already been taken out from the output buffer - _output_predictor.resetVerticalPositionTo(new_vert_pos, delta_z); - - // record the state change - if (_state_reset_status.reset_count.posD == _state_reset_count_prev.posD) { - _state_reset_status.posD_change = delta_z; + _output_predictor.resetAltitudeTo(new_altitude, delta_z); - } else { - // there's already a reset this update, accumulate total delta - _state_reset_status.posD_change += delta_z; - } - - _state_reset_status.reset_count.posD++; + updateVerticalPositionResetStatus(delta_z); #if defined(CONFIG_EKF2_BAROMETER) _baro_b_est.setBias(_baro_b_est.getBias() + delta_z); @@ -166,9 +211,29 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_v #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_TERRAIN) + updateTerrainResetStatus(delta_z); _state.terrain += delta_z; +#endif // CONFIG_EKF2_TERRAIN + + // Reset the timout timer + _time_last_hgt_fuse = _time_delayed_us; +} - // record the state change +void Ekf::updateVerticalPositionResetStatus(const float delta_z) +{ + if (_state_reset_status.reset_count.posD == _state_reset_count_prev.posD) { + _state_reset_status.posD_change = delta_z; + + } else { + // there's already a reset this update, accumulate total delta + _state_reset_status.posD_change += delta_z; + } + + _state_reset_status.reset_count.posD++; +} + +void Ekf::updateTerrainResetStatus(const float delta_z) +{ if (_state_reset_status.reset_count.hagl == _state_reset_count_prev.hagl) { _state_reset_status.hagl_change = delta_z; @@ -178,17 +243,15 @@ void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_v } _state_reset_status.reset_count.hagl++; -#endif // CONFIG_EKF2_TERRAIN - - // Reset the timout timer - _time_last_hgt_fuse = _time_delayed_us; } void Ekf::resetHorizontalPositionToLastKnown() { - ECL_INFO("reset position to last known (%.3f, %.3f)", (double)_last_known_pos(0), (double)_last_known_pos(1)); + ECL_INFO("reset position to last known (%.3f, %.3f)", (double)_last_known_gpos.latitude_deg(), + (double)_last_known_gpos.longitude_deg()); _information_events.flags.reset_pos_to_last_known = true; // Used when falling back to non-aiding mode of operation - resetHorizontalPositionTo(_last_known_pos.xy(), sq(_params.pos_noaid_noise)); + resetHorizontalPositionTo(_last_known_gpos.latitude_deg(), _last_known_gpos.longitude_deg(), + sq(_params.pos_noaid_noise)); } diff --git a/src/modules/ekf2/EKF/terrain_control.cpp b/src/modules/ekf2/EKF/terrain_control.cpp index 323d5ac55349..afb845a662ec 100644 --- a/src/modules/ekf2/EKF/terrain_control.cpp +++ b/src/modules/ekf2/EKF/terrain_control.cpp @@ -43,7 +43,7 @@ void Ekf::initTerrain() { // assume a ground clearance - _state.terrain = _state.pos(2) + _params.rng_gnd_clearance; + _state.terrain = -_gpos.altitude() + _params.rng_gnd_clearance; // use the ground clearance value as our uncertainty P.uncorrelateCovarianceSetVariance(State::terrain.idx, sq(_params.rng_gnd_clearance)); @@ -53,7 +53,7 @@ void Ekf::controlTerrainFakeFusion() { // If we are on ground, store the local position and time to use as a reference if (!_control_status.flags.in_air) { - _last_on_ground_posD = _state.pos(2); + _last_on_ground_posD = -_gpos.altitude(); _control_status.flags.rng_fault = false; } else if (!_control_status_prev.flags.in_air) { diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index a40289f7b340..93c9ed617a0f 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1166,17 +1166,17 @@ void EKF2::PublishEventFlags(const hrt_abstime ×tamp) void EKF2::PublishGlobalPosition(const hrt_abstime ×tamp) { if (_ekf.global_origin_valid() && _ekf.control_status().flags.yaw_align) { - const Vector3f position{_ekf.getPosition()}; - // generate and publish global position data vehicle_global_position_s global_pos{}; global_pos.timestamp_sample = timestamp; - // Position of local NED origin in GPS / WGS84 frame - _ekf.global_origin().reproject(position(0), position(1), global_pos.lat, global_pos.lon); + // Position GPS / WGS84 frame + const LatLonAlt lla = _ekf.getLatLonAlt(); + global_pos.lat = lla.latitude_deg(); + global_pos.lon = lla.longitude_deg(); global_pos.lat_lon_valid = _ekf.isGlobalHorizontalPositionValid(); - global_pos.alt = -position(2) + _ekf.getEkfGlobalOriginAltitude(); // Altitude AMSL in meters + global_pos.alt = lla.altitude(); global_pos.alt_valid = _ekf.isGlobalVerticalPositionValid(); #if defined(CONFIG_EKF2_GNSS) diff --git a/src/modules/ekf2/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp index d1a9e918963a..d905fb85703c 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -180,15 +180,31 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) _ekf->set_vehicle_at_rest(false); _ekf->set_is_fixed_wing(true); + const Vector3f pos_prev = _ekf->getPosition(); + const double latitude_new = -15.0000005; const double longitude_new = -115.0000005; const float altitude_new = 1500.0; const float eph = 50.f; const float epv = 10.f; - _ekf->setEkfGlobalOrigin(latitude_new, longitude_new, altitude_new); _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); + const Vector3f pos = _ekf->getPosition(); + + // lat/lon is initialized so the local horizontal position remains constant + EXPECT_NEAR(pos(0), pos_prev(0), 1e-3f); + EXPECT_NEAR(pos(1), pos_prev(1), 1e-3f); + + // alt is updated as the local altitude origin was already set + EXPECT_NEAR(pos(2), pos_prev(2) - (altitude_new - _ekf->getEkfGlobalOriginAltitude()), 1e-3f); + + const LatLonAlt lla = _ekf->getLatLonAlt(); + EXPECT_NEAR(lla.latitude_deg(), latitude_new, 1e-6f); + EXPECT_NEAR(lla.longitude_deg(), longitude_new, 1e-6f); + EXPECT_NEAR(lla.altitude(), altitude_new, 1e-3f); + + // Simulate the fact that the sideslip can start immediately, without // waiting for a measurement sample. _ekf_wrapper.enableBetaFusion(); @@ -227,7 +243,6 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoningLatLonAltReset) const float eph = 50.f; const float epv = 1.f; - _ekf->setEkfGlobalOrigin(latitude, longitude, altitude); _ekf->resetGlobalPosToExternalObservation(latitude, longitude, altitude, eph, epv, 0); _ekf_wrapper.enableBetaFusion(); diff --git a/src/modules/ekf2/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp index afe56992050d..d67cac0e528a 100644 --- a/src/modules/ekf2/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -219,19 +219,22 @@ TEST_F(EkfBasicsTest, reset_ekf_global_origin_gps_initialized) _altitude_new = 100.0; _sensor_simulator.startGps(); - _ekf->set_min_required_gps_health_time(1e6); - _sensor_simulator.runSeconds(1); + _ekf_wrapper.enableGpsHeightFusion(); _sensor_simulator.setGpsLatitude(_latitude_new); _sensor_simulator.setGpsLongitude(_longitude_new); _sensor_simulator.setGpsAltitude(_altitude_new); + _ekf->set_min_required_gps_health_time(1e6); + _sensor_simulator.runSeconds(1); _sensor_simulator.runSeconds(5); _ekf->getEkfGlobalOrigin(_origin_time, _latitude, _longitude, _altitude); EXPECT_DOUBLE_EQ(_latitude, _latitude_new); EXPECT_DOUBLE_EQ(_longitude, _longitude_new); - EXPECT_NEAR(_altitude, _altitude_new, 0.01f); + + // In baro height ref the origin is set using baro data and not GNSS altitude + EXPECT_NEAR(_altitude, _sensor_simulator._baro.getData(), 0.01f); // Note: we cannot reset too far since the local position is limited to 1e6m _latitude_new = 14.0000005; @@ -261,11 +264,13 @@ TEST_F(EkfBasicsTest, reset_ekf_global_origin_gps_initialized) TEST_F(EkfBasicsTest, reset_ekf_global_origin_gps_uninitialized) { - _ekf->getEkfGlobalOrigin(_origin_time, _latitude_new, _longitude_new, _altitude_new); + _ekf->getEkfGlobalOrigin(_origin_time, _latitude, _longitude, _altitude); EXPECT_DOUBLE_EQ(_latitude, _latitude_new); EXPECT_DOUBLE_EQ(_longitude, _longitude_new); - EXPECT_FLOAT_EQ(_altitude, _altitude_new); + + // In baro height ref the origin is set using baro data and not GNSS altitude + EXPECT_NEAR(_altitude, _sensor_simulator._baro.getData(), 0.01f); EXPECT_FALSE(_ekf->global_origin_valid()); diff --git a/src/modules/ekf2/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp index 650d168a98b7..bc33c350e792 100644 --- a/src/modules/ekf2/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -345,3 +345,49 @@ TEST_F(EkfFlowTest, yawMotionNoMagFusion) _ekf->state().vector().print(); _ekf->covariances().print(); } + +TEST_F(EkfFlowTest, deadReckoning) +{ + ResetLoggingChecker reset_logging_checker(_ekf); + + // WHEN: simulate being 5m above ground + const float simulated_distance_to_ground = 5.f; + _sensor_simulator._trajectory[2].setCurrentPosition(-simulated_distance_to_ground); + startRangeFinderFusion(simulated_distance_to_ground); + + _ekf->set_in_air_status(true); + _ekf->set_vehicle_at_rest(false); + + // WHEN: moving a couple of meters while doing flow dead_reckoning + Vector3f simulated_velocity(0.5f, -0.2f, 0.f); + _sensor_simulator._trajectory[0].setCurrentVelocity(simulated_velocity(0)); + _sensor_simulator._trajectory[1].setCurrentVelocity(simulated_velocity(1)); + _sensor_simulator.setTrajectoryTargetVelocity(simulated_velocity); + _ekf_wrapper.enableFlowFusion(); + _sensor_simulator.startFlow(); + + _sensor_simulator.runTrajectorySeconds(5.f); + + simulated_velocity = Vector3f(0.f, 0.f, 0.f); + _sensor_simulator.setTrajectoryTargetVelocity(simulated_velocity); + + _sensor_simulator.runTrajectorySeconds(_sensor_simulator._trajectory[0].getTotalTime()); + + EXPECT_FALSE(_ekf->isGlobalHorizontalPositionValid()); + EXPECT_TRUE(_ekf->isLocalHorizontalPositionValid()); + const Vector3f lpos_before_reset = _ekf->getPosition(); + const float altitude_ref_prev = _ekf->getEkfGlobalOriginAltitude(); + + const double latitude_new = -15.0000005; + const double longitude_new = -115.0000005; + const float altitude_new = 1500.0; + const float eph = 50.f; + const float epv = 10.f; + _ekf->setEkfGlobalOrigin(latitude_new, longitude_new, altitude_new, eph, epv); + + const Vector3f lpos_after_reset = _ekf->getPosition(); + + EXPECT_NEAR(lpos_after_reset(0), lpos_before_reset(0), 1e-3); + EXPECT_NEAR(lpos_after_reset(1), lpos_before_reset(1), 1e-3); + EXPECT_NEAR(lpos_after_reset(2), lpos_before_reset(2) + (altitude_new - altitude_ref_prev), 1e-3); +} diff --git a/src/modules/ekf2/test/test_EKF_gps.cpp b/src/modules/ekf2/test/test_EKF_gps.cpp index ac683564a473..f6aae937df0b 100644 --- a/src/modules/ekf2/test/test_EKF_gps.cpp +++ b/src/modules/ekf2/test/test_EKF_gps.cpp @@ -164,7 +164,7 @@ TEST_F(EkfGpsTest, resetToGpsPosition) // AND: simulate jump in position _sensor_simulator.startGps(); - const Vector3f simulated_position_change(2.0f, -1.0f, 0.f); + const Vector3f simulated_position_change(20.0f, -1.0f, 0.f); _sensor_simulator._gps.stepHorizontalPositionByMeters( Vector2f(simulated_position_change)); _sensor_simulator.runSeconds(6); diff --git a/src/modules/ekf2/test/test_EKF_height_fusion.cpp b/src/modules/ekf2/test/test_EKF_height_fusion.cpp index b322a2818245..17c95cad453f 100644 --- a/src/modules/ekf2/test/test_EKF_height_fusion.cpp +++ b/src/modules/ekf2/test/test_EKF_height_fusion.cpp @@ -123,7 +123,7 @@ TEST_F(EkfHeightFusionTest, baroRef) /* EXPECT_EQ(status.bias, _sensor_simulator._baro.getData()); */ // This is the real bias, but the estimator isn't running so the status isn't updated EXPECT_EQ(baro_status.bias, 0.f); const BiasEstimator::status &gps_status = _ekf->getGpsHgtBiasEstimatorStatus(); - EXPECT_NEAR(gps_status.bias, -baro_increment, 0.2f); + EXPECT_NEAR(gps_status.bias, _sensor_simulator._gps.getData().alt - _sensor_simulator._baro.getData(), 0.2f); const float terrain = _ekf->getTerrainVertPos(); EXPECT_NEAR(terrain, -baro_increment, 1.2f); @@ -170,8 +170,13 @@ TEST_F(EkfHeightFusionTest, gpsRef) EXPECT_TRUE(_ekf_wrapper.isIntendingRangeHeightFusion()); EXPECT_FALSE(_ekf_wrapper.isIntendingExternalVisionHeightFusion()); - // AND WHEN: the baro data increases const float baro_initial = _sensor_simulator._baro.getData(); + + const BiasEstimator::status &baro_status_initial = _ekf->getBaroBiasEstimatorStatus(); + const float baro_rel_initial = baro_initial - _sensor_simulator._gps.getData().alt; + EXPECT_NEAR(baro_status_initial.bias, baro_rel_initial, 0.6f); + + // AND WHEN: the baro data increases const float baro_increment = 5.f; _sensor_simulator._baro.setData(baro_initial + baro_increment); _sensor_simulator.runSeconds(100); @@ -180,7 +185,7 @@ TEST_F(EkfHeightFusionTest, gpsRef) // the GPS height value and the baro gets its bias estimated EXPECT_NEAR(_ekf->getPosition()(2), 0.f, 1.f); const BiasEstimator::status &baro_status = _ekf->getBaroBiasEstimatorStatus(); - EXPECT_NEAR(baro_status.bias, baro_initial + baro_increment, 1.3f); + EXPECT_NEAR(baro_status.bias, baro_rel_initial + baro_increment, 1.3f); const float terrain = _ekf->getTerrainVertPos(); EXPECT_NEAR(terrain, 0.f, 1.1f); // TODO: why? @@ -196,7 +201,7 @@ TEST_F(EkfHeightFusionTest, gpsRef) EXPECT_TRUE(_ekf_wrapper.isIntendingBaroHeightFusion()); EXPECT_TRUE(_ekf_wrapper.isIntendingGpsHeightFusion()); EXPECT_TRUE(_ekf_wrapper.isIntendingRangeHeightFusion()); - EXPECT_NEAR(_ekf->getBaroBiasEstimatorStatus().bias, baro_initial + baro_increment - gps_step, 0.2f); + EXPECT_NEAR(_ekf->getBaroBiasEstimatorStatus().bias, baro_rel_initial + baro_increment - gps_step, 0.2f); // and the innovations are close to zero EXPECT_NEAR(_ekf->aid_src_baro_hgt().innovation, 0.f, 0.2f); @@ -367,6 +372,7 @@ TEST_F(EkfHeightFusionTest, changeEkfOriginAlt) ResetLoggingChecker reset_logging_checker(_ekf); reset_logging_checker.capturePreResetState(); + const float baro_bias_prev = _ekf->getBaroBiasEstimatorStatus().bias; const float alt_increment = 4478.f; _ekf->setEkfGlobalOrigin(lat, lon, alt + alt_increment); @@ -376,9 +382,12 @@ TEST_F(EkfHeightFusionTest, changeEkfOriginAlt) EXPECT_NEAR(_ekf->getPosition()(2), alt_increment, 1.f); reset_logging_checker.capturePostResetState(); - EXPECT_NEAR(_ekf->getBaroBiasEstimatorStatus().bias, _sensor_simulator._baro.getData() + alt_increment, 0.2f); + + // An origin reset doesn't change the baro bias as it is relative to the height reference (GNSS) + EXPECT_NEAR(_ekf->getBaroBiasEstimatorStatus().bias, baro_bias_prev, 0.3f); EXPECT_NEAR(_ekf->getTerrainVertPos(), alt_increment, 1.f); + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); } diff --git a/src/modules/ekf2/test/test_EKF_yaw_estimator.cpp b/src/modules/ekf2/test/test_EKF_yaw_estimator.cpp index 1a132e5db509..1d1fdfb6ce8d 100644 --- a/src/modules/ekf2/test/test_EKF_yaw_estimator.cpp +++ b/src/modules/ekf2/test/test_EKF_yaw_estimator.cpp @@ -40,7 +40,6 @@ #include "EKF/ekf.h" #include "sensor_simulator/sensor_simulator.h" #include "sensor_simulator/ekf_wrapper.h" -#include "test_helper/reset_logging_checker.h" class EKFYawEstimatorTest : public ::testing::Test { @@ -91,8 +90,6 @@ TEST_F(EKFYawEstimatorTest, inAirYawAlignment) // WHEN: the vehicle starts accelerating in the horizontal plane _sensor_simulator.setTrajectoryTargetVelocity(Vector3f(2.f, -2.f, -1.f)); _ekf->set_in_air_status(true); - ResetLoggingChecker reset_logging_checker(_ekf); - reset_logging_checker.capturePreResetState(); _sensor_simulator.runTrajectorySeconds(3.f); @@ -106,10 +103,12 @@ TEST_F(EKFYawEstimatorTest, inAirYawAlignment) EXPECT_NEAR(yaw_est, yaw, tolerance_rad); EXPECT_LT(yaw_est_var, tolerance_rad); - // 1 reset when starting GNSS aiding - reset_logging_checker.capturePostResetState(); - EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1)); - EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(1)); + EXPECT_LT(_ekf->aid_src_gnss_pos().test_ratio[0], 0.5f); + EXPECT_LT(_ekf->aid_src_gnss_pos().test_ratio[1], 0.5f); + + EXPECT_LT(_ekf->aid_src_gnss_vel().test_ratio[0], 0.1f); + EXPECT_LT(_ekf->aid_src_gnss_vel().test_ratio[1], 0.1f); + EXPECT_LT(_ekf->aid_src_gnss_vel().test_ratio[2], 0.1f); EXPECT_TRUE(_ekf->isLocalHorizontalPositionValid()); EXPECT_TRUE(_ekf->isGlobalHorizontalPositionValid()); From 15f3ea636caeb0355b8584053794d5f2ffc0c810 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 28 Oct 2024 16:54:14 +0100 Subject: [PATCH 02/11] ekf-flow: do not reset position when resetting to flow Flow only provides velocity information --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp index 60238af10572..906e755a2feb 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp @@ -230,14 +230,6 @@ void Ekf::resetFlowFusion(const flowSample &flow_sample) const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(flow_sample); resetHorizontalVelocityTo(getFilteredFlowVelNE(), flow_vel_var); - // reset position, estimate is relative to initial position in this mode, so we start with zero error - if (!_control_status.flags.in_air) { - ECL_INFO("reset position to zero"); - //TODO: reset origin instead? - resetHorizontalPositionToLastKnown(); - // resetHorizontalPositionTo(Vector2f(0.f, 0.f), 0.f); - } - resetAidSourceStatusZeroInnovation(_aid_src_optical_flow); _innov_check_fail_status.flags.reject_optflow_X = false; From 8e183a41c7ad69d9428dd3c47195abc8733c3fba Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 25 Oct 2024 13:10:24 +0200 Subject: [PATCH 03/11] ekf2-derivation: build state struct based on type --- .../python/ekf_derivation/utils/derivation_utils.py | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/utils/derivation_utils.py b/src/modules/ekf2/EKF/python/ekf_derivation/utils/derivation_utils.py index faf431da7167..97a11524318c 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/utils/derivation_utils.py +++ b/src/modules/ekf2/EKF/python/ekf_derivation/utils/derivation_utils.py @@ -91,20 +91,21 @@ def generate_python_function(function_name, output_names): def build_state_struct(state, T="float"): out = "struct StateSample {\n" - def TypeFromLength(len): - if len == 1: + def get_px4_type(obj): + if isinstance(obj, sf.M11): return f"{T}" - elif len == 2: + elif isinstance(obj, sf.M21): return f"matrix::Vector2<{T}>" - elif len == 3: + elif isinstance(obj, sf.M31): return f"matrix::Vector3<{T}>" - elif len == 4: + elif isinstance(obj, sf.Rot3): return f"matrix::Quaternion<{T}>" else: + print(f"unknown type {type(obj)}") raise NotImplementedError for key, val in state.items(): - out += f"\t{TypeFromLength(val.storage_dim())} {key}{{}};\n" + out += f"\t{get_px4_type(val)} {key}{{}};\n" state_size = state.storage_dim() out += f"\n\tmatrix::Vector<{T}, {state_size}> Data() const {{\n" \ From 9088aa6a753dd130ea14b993390d30daa79864d7 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 30 Oct 2024 10:24:58 +0100 Subject: [PATCH 04/11] update change indicator --- .../test/change_indication/ekf_gsf_reset.csv | 780 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 700 ++++++++-------- 2 files changed, 740 insertions(+), 740 deletions(-) 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 02d18bc9eea1..fcf346c1e89d 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.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.032 -90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.058 -190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.082 -290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.1,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.11 -390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.1,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.13 -490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.16 -590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.18 -690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.1,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.21 -790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.23 -890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.26 -990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.28 -1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.31 -1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 -1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 -1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -1490000,1,-0.01,-0.014,0.00016,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.011,-0.014,0.00013,0.028,-0.00014,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.011,-0.014,9.8e-05,0.035,-0.002,-0.2,0.0076,0.00053,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.011,-0.015,7.8e-05,0.043,-0.0033,-0.22,0.011,0.00027,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,8.9e-05,0.036,-0.0048,-0.23,0.0082,-0.00029,-0.19,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 -2090000,1,-0.011,-0.014,5.1e-05,0.041,-0.0073,-0.24,0.012,-0.00089,-0.22,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,6.4e-05,0.033,-0.007,-0.26,0.0079,-0.00099,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,5.1e-05,0.039,-0.0095,-0.27,0.011,-0.0018,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,6.9e-05,0.03,-0.0089,-0.29,0.0074,-0.0015,-0.3,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.013,5.1e-05,0.035,-0.011,-0.3,0.011,-0.0025,-0.32,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.011,-0.013,6.6e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.011,-0.013,6.3e-05,0.03,-0.011,-0.33,0.0097,-0.0028,-0.39,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.011,-0.013,5.8e-05,0.023,-0.0096,-0.34,0.0062,-0.002,-0.42,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.011,-0.013,8.3e-06,0.027,-0.012,-0.35,0.0087,-0.003,-0.46,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.011,-0.013,5.6e-05,0.022,-0.0098,-0.36,0.0057,-0.0021,-0.49,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.011,-0.013,6e-05,0.025,-0.011,-0.38,0.008,-0.0032,-0.53,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.011,-0.013,2.9e-06,0.02,-0.009,-0.39,0.0053,-0.0022,-0.57,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.011,-0.013,4.4e-05,0.023,-0.011,-0.4,0.0074,-0.0032,-0.61,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.011,-0.012,1.5e-05,0.018,-0.0095,-0.42,0.0049,-0.0022,-0.65,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.011,-0.013,8.2e-06,0.022,-0.012,-0.43,0.0069,-0.0033,-0.69,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.011,-0.012,3.2e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.011,-0.012,0.00015,0.019,-0.014,-0.46,0.0065,-0.0036,-0.78,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.011,-0.012,0.0002,0.016,-0.014,-0.47,0.0044,-0.0027,-0.82,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.48,0.006,-0.0041,-0.87,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.011,-0.012,0.00017,0.02,-0.017,-0.5,0.0079,-0.0057,-0.92,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.51,0.0056,-0.0042,-0.97,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.011,-0.012,0.00014,0.02,-0.017,-0.53,0.0075,-0.0058,-1,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.01,-0.012,9.8e-05,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.01,-0.012,0.00012,0.018,-0.013,-0.55,0.0071,-0.0055,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.01,-0.012,0.00018,0.014,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.01,-0.012,0.00021,0.017,-0.012,-0.58,0.0067,-0.0049,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.01,-0.012,0.00021,0.014,-0.01,-0.6,0.0048,-0.0035,-1.3,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.01,-0.012,0.0002,0.015,-0.012,-0.61,0.0062,-0.0045,-1.4,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.01,-0.011,0.00019,0.012,-0.01,-0.63,0.0044,-0.0033,-1.4,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.01,-0.012,0.00017,0.015,-0.011,-0.64,0.0058,-0.0043,-1.5,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.01,-0.011,0.00022,0.011,-0.0085,-0.66,0.0041,-0.0031,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.01,-0.011,0.00024,0.013,-0.0098,-0.67,0.0053,-0.004,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.01,-0.011,0.00023,0.0086,-0.0073,-0.68,0.0037,-0.0029,-1.7,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0099,-0.011,0.00029,0.0081,-0.0081,-0.7,0.0045,-0.0036,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0098,-0.011,0.0003,0.0055,-0.0062,-0.71,0.0031,-0.0026,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0097,-0.011,0.00028,0.0061,-0.0066,-0.73,0.0036,-0.0032,-1.9,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0096,-0.011,0.00036,0.0041,-0.0038,-0.74,0.0025,-0.0022,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0095,-0.011,0.00035,0.0044,-0.0028,-0.75,0.0029,-0.0025,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0095,-0.011,0.00033,0.0038,-0.00092,0.0028,0.002,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0094,-0.011,0.00036,0.0041,0.00056,0.015,0.0023,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0094,-0.011,0.00034,0.0051,0.0017,-0.011,0.0028,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0094,-0.011,0.00027,0.0038,0.0042,-0.005,0.002,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0094,-0.011,0.00024,0.005,0.0043,-0.012,0.0025,-0.00012,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-3.6e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0093,-0.011,0.00026,0.0043,0.0053,-0.05,0.0019,0.00038,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-3.6e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0093,-0.011,0.00026,0.0049,0.0055,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.0093,-0.011,0.00019,0.0037,0.0055,-0.099,0.0018,0.001,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-3.6e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0093,-0.011,0.00012,0.0046,0.0051,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-3.6e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,0.71,0.0012,-0.014,0.71,0.0049,0.0051,-0.11,0.0028,0.0015,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-6.9e-05,0.21,8e-05,0.43,3.6e-05,0.00032,-0.0024,0,0,-3.6e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.11,0.11,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 -6890000,0.71,0.0013,-0.014,0.7,0.00053,0.0064,-0.12,0.0015,0.0026,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-9.7e-05,0.21,1.3e-05,0.43,1.3e-06,0.00089,-0.00086,0,0,-3.6e+02,0.0013,0.0013,0.047,0.21,0.21,0.46,0.13,0.14,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 -6990000,0.71,0.0013,-0.014,0.71,-0.00023,0.0046,-0.12,0.0011,0.0017,-3.7e+02,-0.0015,-0.0057,-7.6e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-3.6e+02,0.0013,0.0013,0.044,0.23,0.24,0.36,0.17,0.17,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 -7090000,0.71,0.0012,-0.014,0.71,-0.00079,0.0011,-0.13,0.0011,0.00014,-3.7e+02,-0.0014,-0.0057,-7.7e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00037,0.00025,-0.00041,0,0,-3.6e+02,0.0013,0.0013,0.043,0.27,0.27,0.29,0.2,0.21,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 -7190000,0.71,0.0013,-0.014,0.71,-0.0025,0.0019,-0.15,0.00089,0.0011,-3.7e+02,-0.0015,-0.0057,-7.7e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-3.6e+02,0.0013,0.0013,0.042,0.3,0.31,0.24,0.25,0.25,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 -7290000,0.71,0.0015,-0.014,0.71,-0.0044,0.0099,-0.15,0.00034,0.0079,-3.7e+02,-0.0016,-0.0057,-7.3e-05,-0.00021,-0.0002,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00039,0,0,-3.6e+02,0.0013,0.0013,0.042,0.34,0.35,0.2,0.3,0.31,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7390000,0.71,0.0016,-0.014,0.71,-0.0037,0.015,-0.16,0.00062,0.012,-3.7e+02,-0.0016,-0.0057,-7.1e-05,-0.00028,-3.8e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00032,0,0,-3.6e+02,0.0013,0.0013,0.041,0.38,0.39,0.18,0.37,0.37,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7490000,0.71,0.0015,-0.014,0.71,-0.0038,0.011,-0.16,0.0014,0.0094,-3.7e+02,-0.0016,-0.0057,-7.2e-05,-0.00018,-7.3e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00078,-0.00043,0,0,-3.6e+02,0.0013,0.0013,0.041,0.43,0.43,0.15,0.44,0.45,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7590000,0.71,0.0016,-0.014,0.71,-0.0034,0.02,-0.17,0.0033,0.018,-3.7e+02,-0.0017,-0.0057,-6.8e-05,-0.00024,0.00021,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-3.6e+02,0.0013,0.0013,0.04,0.48,0.48,0.14,0.53,0.53,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7690000,0.71,0.0016,-0.014,0.71,-0.0046,0.017,-0.16,0.0032,0.016,-3.7e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00032,0.00084,-0.00033,0,0,-3.6e+02,0.0014,0.0013,0.04,0.53,0.53,0.13,0.63,0.63,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 -7790000,0.71,0.0017,-0.014,0.71,-0.011,0.016,-0.16,-0.0031,0.016,-3.7e+02,-0.0016,-0.0057,-7.3e-05,-0.00036,6.2e-05,-0.0071,0.21,-1.6e-05,0.43,-0.00034,0.00078,-0.00038,0,0,-3.6e+02,0.0014,0.0013,0.04,0.58,0.58,0.12,0.74,0.74,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 -7890000,0.71,0.0017,-0.014,0.71,-0.011,0.021,-0.16,-0.00066,0.02,-3.7e+02,-0.0016,-0.0057,-7.1e-05,-0.00038,0.0002,-0.0096,0.21,-1.5e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-3.6e+02,0.0014,0.0014,0.04,0.64,0.63,0.11,0.87,0.86,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 -7990000,0.71,0.0017,-0.014,0.71,-0.0091,0.022,-0.16,0.0022,0.022,-3.7e+02,-0.0016,-0.0056,-6.9e-05,-0.00037,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00085,-0.00038,0,0,-3.6e+02,0.0014,0.0014,0.04,0.7,0.68,0.1,1,0.99,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 -8090000,0.71,0.0017,-0.014,0.71,-0.005,0.024,-0.17,0.0082,0.024,-3.7e+02,-0.0016,-0.0056,-6.7e-05,-0.0003,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00033,0.0009,-0.00035,0,0,-3.6e+02,0.0014,0.0014,0.04,0.76,0.74,0.1,1.2,1.1,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8190000,0.71,0.0017,-0.014,0.71,-0.014,0.028,-0.18,-6.4e-05,0.029,-3.7e+02,-0.0016,-0.0056,-6.9e-05,-0.00043,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-3.6e+02,0.0014,0.0014,0.04,0.82,0.79,0.099,1.4,1.3,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8290000,0.71,0.0017,-0.014,0.71,-0.017,0.021,-0.17,-0.0058,0.022,-3.7e+02,-0.0016,-0.0057,-7.2e-05,-0.00056,0.00031,-0.017,0.21,-1e-05,0.43,-0.00031,0.00079,-0.00035,0,0,-3.6e+02,0.0014,0.0014,0.039,0.88,0.84,0.097,1.6,1.5,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8390000,0.71,0.0017,-0.014,0.71,-0.0012,0.00041,-0.17,0.0038,0.023,-3.7e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.021,0.21,-9.3e-06,0.43,-0.0003,0.00084,-0.00031,0,0,-3.6e+02,0.0014,0.0014,0.039,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,7e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8490000,0.71,0.0017,-0.014,0.71,-0.003,0.0023,-0.17,0.0036,0.023,-3.7e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.025,0.21,-9e-06,0.43,-0.00031,0.0008,-0.00028,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.089,6.2e-05,6.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8590000,0.71,0.0021,-0.014,0.71,-0.00044,0.00093,-0.17,0.0032,0.023,-3.7e+02,-0.0018,-0.0057,-6.8e-05,-0.00051,0.00039,-0.029,0.21,-1.2e-05,0.43,-0.00042,0.00076,-0.00028,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.088,6e-05,6.8e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8690000,0.71,0.002,-0.014,0.71,-0.0034,0.0028,-0.16,0.003,0.023,-3.7e+02,-0.0017,-0.0056,-6.6e-05,-0.00051,0.00039,-0.035,0.21,-1e-05,0.43,-0.00039,0.00084,-0.00029,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.088,5.8e-05,6.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8790000,0.71,0.0019,-0.014,0.71,-0.0057,0.0049,-0.15,0.0026,0.024,-3.7e+02,-0.0017,-0.0057,-6.9e-05,-0.0005,0.00043,-0.041,0.21,-9.1e-06,0.43,-0.00037,0.0008,-0.00029,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.087,5.6e-05,6.6e-05,2.4e-06,0.04,0.04,0.032,0.0013,6.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8890000,0.71,0.0019,-0.014,0.71,-0.0079,0.0055,-0.15,0.0019,0.024,-3.7e+02,-0.0016,-0.0057,-7.1e-05,-0.00063,0.00042,-0.045,0.21,-7.8e-06,0.43,-0.00034,0.00078,-0.00033,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.086,5.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.03,0.0013,6.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -8990000,0.71,0.0018,-0.014,0.71,-0.01,0.0049,-0.14,0.00085,0.024,-3.7e+02,-0.0015,-0.0058,-7.5e-05,-0.00087,0.00044,-0.051,0.21,-6.6e-06,0.43,-0.0003,0.00071,-0.00034,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.087,5.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.029,0.0013,6.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -9090000,0.71,0.002,-0.014,0.71,-0.014,0.006,-0.14,-0.00063,0.025,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.00098,0.00054,-0.053,0.21,-6.9e-06,0.43,-0.00033,0.00068,-0.00034,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1.1e+02,1.1e+02,0.086,4.9e-05,6.2e-05,2.4e-06,0.04,0.04,0.028,0.0013,5.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -9190000,0.71,0.0019,-0.014,0.71,-0.012,0.0087,-0.14,-0.0008,0.026,-3.7e+02,-0.0015,-0.0056,-7e-05,-0.00086,0.00059,-0.057,0.21,-6.2e-06,0.43,-0.00031,0.00081,-0.00025,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.094,1.1e+02,1.1e+02,0.085,4.6e-05,6e-05,2.4e-06,0.04,0.04,0.027,0.0013,5.6e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -9290000,0.71,0.0017,-0.014,0.71,-0.011,0.0086,-0.14,-0.0015,0.026,-3.7e+02,-0.0015,-0.0056,-7.1e-05,-0.00096,0.00059,-0.061,0.21,-5.1e-06,0.43,-0.00026,0.00082,-0.00024,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.093,1.1e+02,1.1e+02,0.085,4.4e-05,5.8e-05,2.4e-06,0.04,0.04,0.025,0.0013,5.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9390000,0.71,0.0015,-0.014,0.71,-0.011,0.0092,-0.14,-0.0023,0.027,-3.7e+02,-0.0014,-0.0056,-7.3e-05,-0.001,0.00058,-0.065,0.21,-4.3e-06,0.43,-0.00022,0.00082,-0.00022,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.093,1.2e+02,1.2e+02,0.086,4.2e-05,5.7e-05,2.4e-06,0.04,0.04,0.024,0.0013,5.2e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9490000,0.71,0.0014,-0.014,0.71,-0.0078,0.011,-0.13,-0.0012,0.028,-3.7e+02,-0.0014,-0.0055,-6.9e-05,-0.001,0.0006,-0.068,0.21,-3.7e-06,0.43,-0.00018,0.0009,-0.00013,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.091,1.2e+02,1.2e+02,0.085,4e-05,5.5e-05,2.4e-06,0.04,0.04,0.023,0.0013,5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9590000,0.71,0.0016,-0.014,0.71,-0.01,0.016,-0.13,-0.0026,0.031,-3.7e+02,-0.0015,-0.0054,-6.6e-05,-0.0011,0.00079,-0.072,0.21,-4.5e-06,0.43,-0.00024,0.00091,-0.00012,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.09,1.3e+02,1.3e+02,0.085,3.8e-05,5.4e-05,2.4e-06,0.04,0.04,0.021,0.0013,4.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9690000,0.71,0.0018,-0.014,0.71,-0.017,0.017,-0.12,-0.0071,0.032,-3.7e+02,-0.0015,-0.0056,-7e-05,-0.0013,0.00092,-0.077,0.21,-4.8e-06,0.43,-0.00027,0.0008,-0.00017,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.089,1.3e+02,1.3e+02,0.086,3.6e-05,5.2e-05,2.4e-06,0.04,0.04,0.02,0.0013,4.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -9790000,0.71,0.0017,-0.014,0.71,-0.013,0.02,-0.11,-0.0063,0.034,-3.7e+02,-0.0015,-0.0055,-6.8e-05,-0.0014,0.001,-0.082,0.21,-4.4e-06,0.43,-0.00024,0.00085,-9.7e-05,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.087,1.4e+02,1.4e+02,0.085,3.4e-05,5e-05,2.4e-06,0.04,0.04,0.019,0.0013,4.5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -9890000,0.71,0.0018,-0.014,0.71,-0.016,0.023,-0.11,-0.0088,0.037,-3.7e+02,-0.0015,-0.0055,-6.8e-05,-0.0015,0.0011,-0.085,0.21,-4.5e-06,0.43,-0.00026,0.00083,-0.0001,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.084,1.4e+02,1.4e+02,0.085,3.2e-05,4.9e-05,2.4e-06,0.04,0.04,0.018,0.0013,4.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -9990000,0.71,0.0019,-0.014,0.71,-0.02,0.021,-0.1,-0.012,0.037,-3.7e+02,-0.0015,-0.0056,-7.1e-05,-0.0016,0.0011,-0.089,0.21,-4.2e-06,0.43,-0.00025,0.00078,-0.00013,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.083,1.5e+02,1.5e+02,0.086,3e-05,4.7e-05,2.4e-06,0.04,0.04,0.017,0.0013,4.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -10090000,0.71,0.002,-0.014,0.71,-0.022,0.025,-0.096,-0.015,0.042,-3.7e+02,-0.0015,-0.0056,-6.9e-05,-0.0017,0.0013,-0.091,0.21,-4.6e-06,0.43,-0.00029,0.00079,-0.00012,0,0,-3.6e+02,0.0013,0.0012,0.039,25,25,0.08,1.6e+02,1.6e+02,0.085,2.9e-05,4.6e-05,2.4e-06,0.04,0.04,0.016,0.0013,4.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10190000,0.71,0.002,-0.013,0.71,-0.033,0.022,-0.096,-0.025,0.04,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-0.0019,0.0013,-0.093,0.21,-4.5e-06,0.43,-0.00027,0.00065,-0.00015,0,0,-3.6e+02,0.0012,0.0012,0.039,25,25,0.078,1.7e+02,1.7e+02,0.084,2.7e-05,4.4e-05,2.4e-06,0.04,0.04,0.014,0.0013,4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10290000,0.71,0.002,-0.013,0.71,-0.04,0.017,-0.084,-0.033,0.038,-3.7e+02,-0.0015,-0.0058,-7.8e-05,-0.0021,0.0014,-0.098,0.21,-4.2e-06,0.43,-0.00026,0.00058,-0.00017,0,0,-3.6e+02,0.0012,0.0012,0.039,25,25,0.076,1.8e+02,1.8e+02,0.085,2.6e-05,4.2e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10390000,0.71,0.0018,-0.013,0.71,0.0091,-0.02,0.0093,0.00085,-0.0018,-3.7e+02,-0.0015,-0.0058,-7.9e-05,-0.0021,0.0013,-0.098,0.21,-3.7e-06,0.43,-0.00023,0.0006,-0.00014,0,0,-3.6e+02,0.0012,0.0012,0.039,0.25,0.25,0.56,0.25,0.25,0.077,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10490000,0.71,0.0018,-0.013,0.71,0.0071,-0.019,0.022,0.0016,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.3e-05,-0.0022,0.0013,-0.098,0.21,-3.3e-06,0.43,-0.00021,0.00053,-0.00016,0,0,-3.6e+02,0.0012,0.0012,0.039,0.26,0.26,0.55,0.26,0.26,0.079,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10590000,0.71,0.0022,-0.013,0.71,0.006,-0.0081,0.024,0.0018,-0.00082,-3.7e+02,-0.0016,-0.0059,-7.9e-05,-0.0024,0.0018,-0.098,0.21,-4.5e-06,0.43,-0.00029,0.00053,-0.00017,0,0,-3.6e+02,0.0012,0.0011,0.039,0.13,0.13,0.27,0.13,0.13,0.072,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10690000,0.71,0.0021,-0.013,0.71,0.0032,-0.009,0.027,0.0023,-0.0017,-3.7e+02,-0.0015,-0.0059,-8.1e-05,-0.0024,0.0018,-0.098,0.21,-4.1e-06,0.43,-0.00027,0.00052,-0.00017,0,0,-3.6e+02,0.0012,0.0011,0.039,0.14,0.14,0.26,0.14,0.14,0.077,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10790000,0.71,0.002,-0.013,0.71,0.0033,-0.0063,0.021,0.0026,-0.00085,-3.7e+02,-0.0015,-0.0059,-8e-05,-0.0025,0.0021,-0.098,0.21,-4e-06,0.43,-0.00026,0.00056,-0.00016,0,0,-3.6e+02,0.0012,0.0011,0.038,0.093,0.093,0.17,0.09,0.09,0.071,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10890000,0.71,0.0019,-0.013,0.71,0.0021,-0.0065,0.016,0.0029,-0.0015,-3.7e+02,-0.0015,-0.0058,-8.1e-05,-0.0025,0.0021,-0.098,0.21,-3.7e-06,0.43,-0.00025,0.00057,-0.00015,0,0,-3.6e+02,0.0011,0.0011,0.038,0.1,0.1,0.16,0.096,0.096,0.074,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -10990000,0.71,0.0017,-0.014,0.71,0.0067,-0.0015,0.011,0.0048,-0.0026,-3.7e+02,-0.0013,-0.0057,-7.9e-05,-0.0025,0.0031,-0.098,0.21,-3.2e-06,0.43,-0.00022,0.00071,-0.00011,0,0,-3.6e+02,0.0011,0.001,0.038,0.079,0.08,0.12,0.072,0.072,0.071,1.7e-05,3.1e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11090000,0.71,0.0017,-0.014,0.71,0.0067,0.0018,0.014,0.0057,-0.0023,-3.7e+02,-0.0014,-0.0056,-7.5e-05,-0.0023,0.0029,-0.098,0.21,-3.3e-06,0.43,-0.00023,0.00078,-6.8e-05,0,0,-3.6e+02,0.0011,0.00099,0.038,0.09,0.091,0.12,0.078,0.078,0.073,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11190000,0.71,0.0017,-0.014,0.71,0.01,0.0033,0.0027,0.0067,-0.0032,-3.7e+02,-0.0013,-0.0056,-7.8e-05,-0.0022,0.004,-0.098,0.21,-3.4e-06,0.43,-0.00024,0.00079,-8.6e-05,0,0,-3.6e+02,0.00098,0.00091,0.038,0.073,0.074,0.091,0.062,0.062,0.068,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11290000,0.71,0.0016,-0.014,0.71,0.0093,0.0017,0.0014,0.0076,-0.0034,-3.7e+02,-0.0013,-0.0057,-8.3e-05,-0.0026,0.0043,-0.098,0.21,-3e-06,0.43,-0.00022,0.00073,-0.00011,0,0,-3.6e+02,0.00097,0.0009,0.038,0.085,0.087,0.087,0.068,0.068,0.071,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11390000,0.71,0.0016,-0.013,0.71,0.0047,0.0008,-0.0044,0.0055,-0.003,-3.7e+02,-0.0013,-0.0058,-8.6e-05,-0.0033,0.0041,-0.098,0.21,-3e-06,0.43,-0.00021,0.00066,-0.00016,0,0,-3.6e+02,0.00086,0.00082,0.038,0.071,0.073,0.072,0.056,0.056,0.067,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11490000,0.71,0.0014,-0.013,0.71,0.00093,-0.0021,-0.0044,0.0055,-0.0039,-3.7e+02,-0.0012,-0.0059,-9.3e-05,-0.0039,0.0049,-0.098,0.21,-2.7e-06,0.43,-0.00018,0.00056,-0.00022,0,0,-3.6e+02,0.00086,0.00081,0.038,0.083,0.085,0.069,0.062,0.062,0.068,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11590000,0.71,0.0013,-0.013,0.71,-0.0022,-0.0016,-0.01,0.0044,-0.0032,-3.7e+02,-0.0012,-0.0059,-9.4e-05,-0.0045,0.0051,-0.098,0.21,-2.5e-06,0.43,-0.00016,0.00054,-0.00023,0,0,-3.6e+02,0.00075,0.00072,0.038,0.07,0.072,0.059,0.052,0.052,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11690000,0.71,0.0011,-0.013,0.71,-0.0037,-0.0027,-0.016,0.0044,-0.004,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0053,0.0052,-0.098,0.21,-2e-06,0.43,-0.0001,0.00053,-0.00026,0,0,-3.6e+02,0.00075,0.00071,0.038,0.081,0.084,0.057,0.059,0.059,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11790000,0.71,0.0011,-0.013,0.71,-0.0077,-0.00091,-0.018,0.0024,-0.002,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0071,0.0054,-0.098,0.21,-2e-06,0.43,-8.7e-05,0.0005,-0.00027,0,0,-3.6e+02,0.00065,0.00063,0.038,0.068,0.07,0.051,0.05,0.05,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11890000,0.71,0.00095,-0.013,0.71,-0.0087,-0.0038,-0.02,0.0016,-0.0027,-3.7e+02,-0.001,-0.006,-0.0001,-0.0077,0.0059,-0.098,0.21,-2e-06,0.43,-5.6e-05,0.00047,-0.00032,0,0,-3.6e+02,0.00065,0.00062,0.038,0.079,0.082,0.049,0.057,0.057,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11990000,0.71,0.0013,-0.013,0.71,-0.012,0.0011,-0.026,-0.0001,-7.8e-05,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0073,0.0065,-0.097,0.21,-2.9e-06,0.43,-0.00013,0.00048,-0.00032,0,0,-3.6e+02,0.00056,0.00055,0.037,0.066,0.068,0.045,0.049,0.049,0.062,9.2e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -12090000,0.71,0.0014,-0.013,0.71,-0.013,0.0043,-0.032,-0.0014,0.00091,-3.7e+02,-0.0012,-0.0059,-9.5e-05,-0.0063,0.0057,-0.097,0.21,-3e-06,0.43,-0.00016,0.00053,-0.00028,0,0,-3.6e+02,0.00056,0.00055,0.037,0.077,0.079,0.045,0.056,0.056,0.062,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12190000,0.71,0.0012,-0.013,0.71,-0.0069,0.0039,-0.026,0.0015,0.00037,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0061,0.006,-0.099,0.21,-2.4e-06,0.43,-0.00011,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.064,0.066,0.041,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12290000,0.71,0.001,-0.013,0.71,-0.0081,0.0044,-0.026,0.0011,0.00072,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0067,0.0056,-0.099,0.21,-2e-06,0.43,-8.3e-05,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.073,0.076,0.042,0.055,0.056,0.06,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12390000,0.71,0.001,-0.013,0.71,-0.0054,0.0032,-0.023,0.0025,0.00024,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0053,0.0073,-0.1,0.21,-2.5e-06,0.43,-0.00012,0.00061,-0.00025,0,0,-3.6e+02,0.00042,0.00043,0.037,0.061,0.063,0.039,0.048,0.048,0.058,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12490000,0.71,0.00094,-0.013,0.71,-0.0071,0.0027,-0.027,0.0017,3.4e-05,-3.7e+02,-0.0011,-0.0059,-0.0001,-0.0058,0.0085,-0.1,0.21,-2.7e-06,0.43,-0.00015,0.00055,-0.00025,0,0,-3.6e+02,0.00042,0.00042,0.037,0.069,0.072,0.04,0.055,0.055,0.058,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12590000,0.71,0.0011,-0.013,0.71,-0.014,0.0037,-0.033,-0.0033,0.00021,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0051,0.0079,-0.1,0.21,-3e-06,0.43,-0.00019,0.00051,-0.00024,0,0,-3.6e+02,0.00037,0.00038,0.037,0.058,0.059,0.038,0.047,0.047,0.057,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12690000,0.71,0.0014,-0.013,0.71,-0.017,0.0046,-0.037,-0.0058,0.00079,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0033,0.0092,-0.1,0.21,-3.9e-06,0.43,-0.00026,0.0005,-0.00025,0,0,-3.6e+02,0.00037,0.00038,0.037,0.065,0.067,0.039,0.055,0.055,0.057,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12790000,0.71,0.0012,-0.013,0.71,-0.02,0.0027,-0.041,-0.0081,0.00025,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0049,0.008,-0.1,0.21,-3.3e-06,0.43,-0.0002,0.00048,-0.00027,0,0,-3.6e+02,0.00033,0.00034,0.037,0.054,0.056,0.037,0.047,0.047,0.056,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12890000,0.71,0.0011,-0.013,0.71,-0.02,0.0014,-0.039,-0.0096,0.00019,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0062,0.0077,-0.1,0.21,-2.9e-06,0.43,-0.00017,0.00047,-0.00026,0,0,-3.6e+02,0.00033,0.00034,0.037,0.061,0.063,0.038,0.054,0.055,0.057,6e-06,1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -12990000,0.71,0.001,-0.013,0.71,-0.009,0.0019,-0.039,-0.0018,0.0005,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0038,0.0081,-0.1,0.21,-2.7e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-3.6e+02,0.0003,0.00031,0.037,0.051,0.053,0.037,0.047,0.047,0.055,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13090000,0.71,0.00095,-0.013,0.71,-0.0097,-0.00015,-0.039,-0.0029,-7.2e-05,-3.7e+02,-0.0011,-0.006,-0.0001,-0.005,0.0097,-0.1,0.21,-3.1e-06,0.43,-0.0002,0.00052,-0.00023,0,0,-3.6e+02,0.0003,0.00031,0.037,0.057,0.059,0.038,0.054,0.054,0.056,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13190000,0.71,0.00094,-0.013,0.71,-0.0023,0.00081,-0.034,0.0028,0.00014,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0032,0.011,-0.11,0.21,-3.4e-06,0.43,-0.00023,0.00056,-0.00021,0,0,-3.6e+02,0.00027,0.00028,0.037,0.048,0.05,0.037,0.047,0.047,0.054,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13290000,0.71,0.00079,-0.013,0.71,-0.00079,0.0015,-0.029,0.0034,0.0003,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0047,0.0096,-0.11,0.21,-2.5e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-3.6e+02,0.00027,0.00028,0.037,0.054,0.055,0.038,0.054,0.054,0.055,5.1e-06,8.9e-06,2.3e-06,0.015,0.018,0.0097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13390000,0.71,0.0007,-0.013,0.71,0.00023,0.0023,-0.024,0.0025,0.00042,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0041,0.0089,-0.11,0.21,-2.3e-06,0.43,-0.00016,0.00063,-0.00019,0,0,-3.6e+02,0.00025,0.00026,0.037,0.045,0.047,0.037,0.047,0.047,0.054,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13490000,0.71,0.00071,-0.013,0.71,0.00021,0.0024,-0.022,0.0027,0.0008,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0042,0.0081,-0.11,0.21,-2e-06,0.43,-0.00015,0.00063,-0.00017,0,0,-3.6e+02,0.00025,0.00026,0.037,0.05,0.052,0.038,0.054,0.054,0.055,4.7e-06,8.2e-06,2.3e-06,0.014,0.017,0.009,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13590000,0.71,0.00072,-0.013,0.71,-2.7e-05,0.0028,-0.024,0.0015,0.00038,-3.7e+02,-0.001,-0.0059,-0.0001,-0.004,0.0094,-0.11,0.21,-2.4e-06,0.43,-0.00017,0.00062,-0.00019,0,0,-3.6e+02,0.00023,0.00025,0.037,0.042,0.044,0.037,0.046,0.047,0.054,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13690000,0.71,0.00071,-0.013,0.71,0.00091,0.0053,-0.029,0.0017,0.0011,-3.7e+02,-0.001,-0.0059,-9.9e-05,-0.0034,0.0082,-0.11,0.21,-2.1e-06,0.43,-0.00016,0.00064,-0.00016,0,0,-3.6e+02,0.00023,0.00024,0.037,0.047,0.049,0.038,0.053,0.054,0.055,4.3e-06,7.7e-06,2.3e-06,0.013,0.017,0.0083,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13790000,0.71,0.00075,-0.013,0.71,0.0006,0.0021,-0.03,0.0024,-0.00073,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.002,0.0089,-0.11,0.21,-2.5e-06,0.43,-0.00019,0.00065,-0.00015,0,0,-3.6e+02,0.00022,0.00023,0.037,0.04,0.041,0.036,0.046,0.046,0.053,4.2e-06,7.3e-06,2.3e-06,0.012,0.016,0.0078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13890000,0.71,0.00059,-0.013,0.71,0.0024,0.0022,-0.035,0.003,-0.00056,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0034,0.0078,-0.11,0.21,-1.8e-06,0.43,-0.00015,0.00065,-0.00015,0,0,-3.6e+02,0.00022,0.00023,0.037,0.044,0.045,0.037,0.053,0.053,0.055,4e-06,7.1e-06,2.3e-06,0.012,0.016,0.0076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13990000,0.71,0.00066,-0.013,0.71,0.0019,0.00054,-0.034,0.0036,-0.0019,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0021,0.0083,-0.11,0.21,-2e-06,0.43,-0.00018,0.00065,-0.00013,0,0,-3.6e+02,0.0002,0.00022,0.037,0.037,0.039,0.036,0.046,0.046,0.054,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0071,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -14090000,0.71,0.00072,-0.013,0.71,0.0014,0.0019,-0.035,0.0036,-0.0013,-3.7e+02,-0.0011,-0.0059,-9.4e-05,-0.00063,0.0073,-0.11,0.21,-1.8e-06,0.43,-0.00018,0.00069,-9.7e-05,0,0,-3.6e+02,0.00021,0.00022,0.037,0.041,0.043,0.036,0.053,0.053,0.054,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14190000,0.71,0.00068,-0.013,0.71,0.0044,0.0019,-0.037,0.0057,-0.001,-3.7e+02,-0.0011,-0.0059,-9.3e-05,-0.00017,0.007,-0.11,0.21,-1.6e-06,0.43,-0.00018,0.00071,-8e-05,0,0,-3.6e+02,0.0002,0.00021,0.037,0.035,0.037,0.035,0.046,0.046,0.054,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14290000,0.71,0.00075,-0.013,0.71,0.0046,0.0032,-0.035,0.0059,-0.00065,-3.7e+02,-0.0011,-0.0058,-9.2e-05,0.00068,0.007,-0.11,0.21,-1.8e-06,0.43,-0.00019,0.00071,-6.2e-05,0,0,-3.6e+02,0.0002,0.0002,0.037,0.038,0.04,0.036,0.052,0.052,0.055,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14390000,0.71,0.00064,-0.014,0.71,0.0071,0.005,-0.037,0.0077,-0.00036,-3.7e+02,-0.0011,-0.0058,-8.9e-05,0.00035,0.0055,-0.11,0.21,-9.2e-07,0.43,-0.00015,0.00074,-4.6e-05,0,0,-3.6e+02,0.00019,0.0002,0.037,0.033,0.035,0.034,0.046,0.046,0.053,3.4e-06,6e-06,2.3e-06,0.011,0.014,0.0059,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14490000,0.71,0.00053,-0.013,0.71,0.008,0.0065,-0.041,0.0088,0.00011,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.00096,0.005,-0.11,0.21,-4.4e-07,0.43,-0.00013,0.0007,-4.6e-05,0,0,-3.6e+02,0.00019,0.00019,0.037,0.036,0.038,0.035,0.052,0.052,0.054,3.3e-06,5.8e-06,2.3e-06,0.011,0.014,0.0057,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14590000,0.71,0.00042,-0.013,0.71,0.0061,0.005,-0.041,0.006,-0.0015,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.0018,0.0047,-0.11,0.21,-3.4e-07,0.43,-0.00012,0.00067,-5.9e-05,0,0,-3.6e+02,0.00018,0.00019,0.037,0.031,0.033,0.033,0.045,0.045,0.054,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0053,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14690000,0.71,0.00037,-0.013,0.71,0.0079,0.0031,-0.038,0.0068,-0.00088,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0018,0.0038,-0.11,0.21,3.8e-08,0.43,-0.0001,0.00068,-4.5e-05,0,0,-3.6e+02,0.00018,0.00019,0.037,0.034,0.036,0.034,0.051,0.052,0.054,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14790000,0.71,0.00035,-0.013,0.71,0.0055,0.0016,-0.033,0.0042,-0.0021,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.002,0.0037,-0.12,0.21,-2e-08,0.43,-0.00011,0.00066,-4.6e-05,0,0,-3.6e+02,0.00017,0.00018,0.037,0.03,0.031,0.032,0.045,0.045,0.053,3e-06,5.2e-06,2.3e-06,0.0097,0.013,0.0048,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14890000,0.71,0.00032,-0.013,0.71,0.0077,0.0034,-0.037,0.005,-0.0018,-3.7e+02,-0.001,-0.0058,-8.6e-05,-0.0022,0.0032,-0.12,0.21,2.4e-07,0.43,-9.1e-05,0.00067,-4.3e-05,0,0,-3.6e+02,0.00017,0.00018,0.037,0.032,0.034,0.032,0.051,0.051,0.055,2.9e-06,5.1e-06,2.3e-06,0.0096,0.013,0.0046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -14990000,0.71,0.00027,-0.013,0.71,0.0068,0.0024,-0.032,0.004,-0.0017,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0028,0.0037,-0.12,0.21,4.6e-08,0.43,-0.0001,0.00064,-5.6e-05,0,0,-3.6e+02,0.00017,0.00017,0.037,0.028,0.03,0.031,0.045,0.045,0.053,2.8e-06,4.9e-06,2.3e-06,0.0094,0.012,0.0043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15090000,0.71,0.0002,-0.013,0.71,0.0075,0.0025,-0.035,0.0047,-0.0016,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0028,0.0041,-0.12,0.21,-5.6e-08,0.43,-0.00011,0.00063,-5.7e-05,0,0,-3.6e+02,0.00017,0.00017,0.037,0.03,0.032,0.031,0.05,0.051,0.054,2.7e-06,4.8e-06,2.3e-06,0.0092,0.012,0.0041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15190000,0.71,0.00017,-0.013,0.7,0.0073,0.003,-0.033,0.0039,-0.0015,-3.7e+02,-0.001,-0.0058,-9e-05,-0.0035,0.0044,-0.12,0.21,-5.2e-08,0.43,-0.00012,0.00059,-6.4e-05,0,0,-3.6e+02,0.00016,0.00017,0.037,0.027,0.028,0.03,0.044,0.045,0.053,2.6e-06,4.6e-06,2.3e-06,0.009,0.012,0.0038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15290000,0.71,0.00019,-0.013,0.7,0.0077,0.0041,-0.03,0.0044,-0.00097,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0026,0.0042,-0.12,0.21,-8.2e-09,0.43,-0.00014,0.00059,-3.9e-05,0,0,-3.6e+02,0.00016,0.00017,0.037,0.029,0.031,0.03,0.05,0.05,0.054,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15390000,0.71,0.0002,-0.013,0.7,0.007,0.0054,-0.028,0.0017,-0.00041,-3.7e+02,-0.001,-0.0058,-8.3e-05,-0.0018,0.0027,-0.12,0.21,3.4e-07,0.43,-0.00012,0.00062,-1.6e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.025,0.027,0.028,0.044,0.044,0.053,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15490000,0.71,0.00022,-0.013,0.7,0.0086,0.0045,-0.028,0.0024,-0.00036,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0022,0.004,-0.12,0.21,-1.1e-07,0.43,-0.00014,0.00059,-3.5e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.027,0.029,0.029,0.049,0.05,0.054,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15590000,0.71,0.00018,-0.013,0.71,0.0072,0.0036,-0.027,8.4e-05,-0.00068,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0028,0.0047,-0.12,0.21,-4.6e-07,0.43,-0.00014,0.00058,-6.1e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.024,0.026,0.027,0.044,0.044,0.053,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15690000,0.71,0.00022,-0.013,0.71,0.0074,0.0037,-0.028,0.00059,-0.00037,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0023,0.0052,-0.12,0.21,-7.6e-07,0.43,-0.00015,0.00059,-6.4e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.026,0.028,0.027,0.049,0.049,0.053,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15790000,0.71,0.00019,-0.013,0.7,0.0081,0.0021,-0.03,0.00049,-0.0016,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0026,0.0054,-0.12,0.21,-8.8e-07,0.43,-0.00016,0.00057,-6.8e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.023,0.025,0.026,0.043,0.044,0.052,2.2e-06,3.9e-06,2.3e-06,0.0081,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15890000,0.71,0.0002,-0.013,0.71,0.0088,0.0021,-0.028,0.0011,-0.0014,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0018,0.0057,-0.12,0.21,-1.1e-06,0.43,-0.00018,0.00057,-6e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.025,0.027,0.026,0.048,0.049,0.053,2.1e-06,3.8e-06,2.3e-06,0.008,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15990000,0.71,0.00018,-0.013,0.71,0.0086,0.0022,-0.024,0.00076,-0.0019,-3.7e+02,-0.0011,-0.0059,-8.4e-05,-0.0012,0.0049,-0.12,0.21,-9.8e-07,0.43,-0.00018,0.00058,-4.2e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.022,0.024,0.025,0.043,0.043,0.052,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -16090000,0.71,0.00021,-0.013,0.71,0.011,0.0039,-0.02,0.0016,-0.0011,-3.7e+02,-0.0011,-0.0058,-8e-05,-0.00043,0.0037,-0.12,0.21,-7.1e-07,0.43,-0.00016,0.00063,-2.6e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.024,0.026,0.024,0.048,0.048,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16190000,0.71,0.00026,-0.013,0.71,0.01,0.0041,-0.019,0.001,-0.00095,-3.7e+02,-0.0011,-0.0058,-7.9e-05,0.00031,0.0039,-0.12,0.21,-1e-06,0.43,-0.00017,0.00063,-2.1e-05,0,0,-3.6e+02,0.00015,0.00014,0.037,0.021,0.023,0.023,0.043,0.043,0.052,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16290000,0.71,0.00028,-0.014,0.71,0.012,0.0052,-0.02,0.0023,5.7e-05,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.00063,0.0026,-0.12,0.21,-5.6e-07,0.43,-0.00015,0.00065,-5.9e-06,0,0,-3.6e+02,0.00015,0.00014,0.037,0.023,0.025,0.023,0.047,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16390000,0.71,0.00033,-0.013,0.71,0.01,0.0037,-0.019,0.0013,-0.00022,-3.7e+02,-0.0011,-0.0058,-7.6e-05,0.0018,0.0038,-0.12,0.21,-1.3e-06,0.43,-0.00018,0.00064,-2e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.022,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0075,0.0098,0.002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16490000,0.71,0.00042,-0.013,0.71,0.0088,0.005,-0.022,0.0018,0.00032,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.0026,0.0039,-0.12,0.21,-1.6e-06,0.43,-0.00019,0.00064,1.2e-05,0,0,-3.6e+02,0.00014,0.00014,0.037,0.022,0.024,0.022,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0019,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16590000,0.71,0.00053,-0.013,0.71,0.0068,0.0059,-0.023,-0.00051,0.0023,-3.7e+02,-0.0012,-0.0058,-7.6e-05,0.0028,0.0036,-0.12,0.21,-1.6e-06,0.43,-0.00017,0.00063,7.8e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.021,0.042,0.042,0.05,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0095,0.0018,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16690000,0.71,0.00049,-0.013,0.71,0.0076,0.0062,-0.019,0.00033,0.0026,-3.7e+02,-0.0012,-0.0058,-7.9e-05,0.0022,0.0043,-0.12,0.21,-1.8e-06,0.43,-0.00018,0.00062,-3.3e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.021,0.024,0.021,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0017,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16790000,0.71,0.00049,-0.013,0.71,0.0058,0.0069,-0.018,-0.0016,0.0042,-3.7e+02,-0.0012,-0.0058,-8e-05,0.002,0.004,-0.12,0.21,-1.7e-06,0.43,-0.00016,0.00063,-1.6e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.019,0.021,0.02,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0092,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16890000,0.71,0.00054,-0.013,0.71,0.0055,0.0078,-0.016,-0.0013,0.0047,-3.7e+02,-0.0012,-0.0058,-8.2e-05,0.0023,0.0046,-0.13,0.21,-2e-06,0.43,-0.00017,0.00062,-1.2e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.02,0.023,0.02,0.046,0.047,0.05,1.6e-06,2.8e-06,2.3e-06,0.007,0.0091,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -16990000,0.71,0.00051,-0.013,0.71,0.0055,0.0055,-0.015,-0.0021,0.0025,-3.7e+02,-0.0012,-0.0059,-8.2e-05,0.0022,0.0056,-0.13,0.21,-2.5e-06,0.43,-0.00019,0.00061,-2.2e-05,0,0,-3.6e+02,0.00013,0.00013,0.037,0.018,0.021,0.019,0.041,0.042,0.049,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17090000,0.71,0.00055,-0.013,0.71,0.0058,0.0071,-0.015,-0.002,0.0032,-3.7e+02,-0.0012,-0.0059,-8.1e-05,0.0032,0.0059,-0.13,0.21,-2.8e-06,0.43,-0.0002,0.00061,-1e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.02,0.022,0.019,0.046,0.047,0.049,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17190000,0.71,0.00061,-0.013,0.71,0.0059,0.008,-0.016,-0.0028,0.0021,-3.7e+02,-0.0012,-0.0059,-7.7e-05,0.004,0.0059,-0.13,0.21,-3.1e-06,0.43,-0.0002,0.00062,-7.9e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.018,0.02,0.018,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0087,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17290000,0.71,0.00063,-0.013,0.71,0.0077,0.0088,-0.011,-0.0026,0.0025,-3.7e+02,-0.0012,-0.0059,-7.9e-05,0.0043,0.0068,-0.13,0.21,-3.5e-06,0.43,-0.00022,0.00061,-5.3e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.019,0.022,0.018,0.045,0.046,0.049,1.5e-06,2.5e-06,2.3e-06,0.0067,0.0086,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17390000,0.71,0.00068,-0.013,0.71,0.0075,0.0092,-0.0095,-0.0024,0.0016,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.0051,0.0066,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.017,0.02,0.017,0.041,0.041,0.048,1.4e-06,2.4e-06,2.2e-06,0.0066,0.0085,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17490000,0.71,0.00063,-0.013,0.71,0.0091,0.0093,-0.0078,-0.0012,0.0025,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.0045,0.0064,-0.13,0.21,-3.4e-06,0.43,-0.00023,0.00061,7.6e-06,0,0,-3.6e+02,0.00013,0.00012,0.037,0.019,0.021,0.017,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17590000,0.71,0.0006,-0.013,0.71,0.0099,0.0085,-0.0024,-0.001,0.0013,-3.7e+02,-0.0012,-0.0059,-7e-05,0.0048,0.0066,-0.13,0.21,-3.7e-06,0.43,-0.00024,0.00061,4.9e-06,0,0,-3.6e+02,0.00013,0.00012,0.037,0.017,0.019,0.017,0.04,0.041,0.048,1.4e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17690000,0.71,0.00058,-0.013,0.71,0.011,0.01,-0.003,1.7e-05,0.0023,-3.7e+02,-0.0012,-0.0059,-6.9e-05,0.0049,0.0064,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.045,0.046,0.048,1.3e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17790000,0.71,0.00056,-0.013,0.71,0.012,0.011,-0.0042,1.3e-05,0.0029,-3.7e+02,-0.0012,-0.0058,-6e-05,0.0059,0.0053,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00064,2.2e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.001,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17890000,0.71,0.00055,-0.013,0.71,0.015,0.012,-0.0041,0.0016,0.0045,-3.7e+02,-0.0012,-0.0058,-5.7e-05,0.0057,0.0046,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00064,2.7e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.018,0.02,0.016,0.044,0.045,0.047,1.3e-06,2.2e-06,2.2e-06,0.0062,0.008,0.00097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17990000,0.71,0.00049,-0.013,0.71,0.016,0.0091,-0.0027,0.0018,0.0036,-3.7e+02,-0.0012,-0.0058,-5.6e-05,0.0054,0.0049,-0.13,0.21,-3.4e-06,0.43,-0.00024,0.00064,2.4e-05,0,0,-3.6e+02,0.00012,0.00012,0.037,0.016,0.019,0.015,0.04,0.041,0.046,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0078,0.00092,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -18090000,0.71,0.00048,-0.013,0.71,0.017,0.0083,-0.00045,0.0035,0.0037,-3.7e+02,-0.0012,-0.0059,-6.2e-05,0.0049,0.0059,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00061,1.9e-05,0,0,-3.6e+02,0.00012,0.00012,0.037,0.017,0.02,0.015,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00089,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18190000,0.71,0.00044,-0.013,0.71,0.018,0.0093,0.001,0.0041,0.0036,-3.7e+02,-0.0012,-0.0059,-5.7e-05,0.0051,0.0056,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00062,2e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.018,0.014,0.04,0.04,0.046,1.2e-06,2e-06,2.2e-06,0.0061,0.0076,0.00085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18290000,0.71,0.00035,-0.013,0.71,0.018,0.0088,0.0022,0.0061,0.0041,-3.7e+02,-0.0012,-0.0059,-6e-05,0.0047,0.0059,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00061,1.4e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.017,0.02,0.014,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00082,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18390000,0.71,0.00032,-0.013,0.71,0.02,0.011,0.0035,0.0068,0.0042,-3.7e+02,-0.0012,-0.0059,-5.4e-05,0.0045,0.0051,-0.13,0.21,-3.4e-06,0.43,-0.00024,0.00062,1.6e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18490000,0.71,0.00038,-0.013,0.71,0.021,0.012,0.0031,0.0085,0.0055,-3.7e+02,-0.0012,-0.0059,-5.3e-05,0.005,0.0052,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00063,1.9e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.02,0.014,0.043,0.045,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18590000,0.71,0.00039,-0.013,0.71,0.02,0.013,0.0014,0.0074,0.0054,-3.7e+02,-0.0012,-0.0058,-4.5e-05,0.0058,0.0047,-0.13,0.21,-3.7e-06,0.43,-0.00025,0.00065,2.5e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0073,0.00072,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18690000,0.71,0.00031,-0.013,0.71,0.022,0.013,-0.00039,0.01,0.0065,-3.7e+02,-0.0012,-0.0059,-4.7e-05,0.0051,0.0047,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00064,1.8e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1e-06,1.8e-06,2.2e-06,0.0058,0.0072,0.0007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18790000,0.71,0.00032,-0.013,0.71,0.021,0.012,-0.00061,0.0087,0.0054,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0053,0.0053,-0.13,0.21,-3.8e-06,0.43,-0.00025,0.00063,1.5e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00067,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18890000,0.71,0.00041,-0.013,0.71,0.021,0.014,1.9e-05,0.01,0.0075,-3.7e+02,-0.0012,-0.0058,-4e-05,0.0062,0.0047,-0.13,0.21,-3.9e-06,0.43,-0.00026,0.00065,2.9e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.007,0.00065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -18990000,0.71,0.00046,-0.013,0.71,0.021,0.015,-0.0012,0.01,0.0068,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0069,0.0049,-0.13,0.21,-4.2e-06,0.43,-0.00027,0.00066,3e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.017,0.012,0.039,0.04,0.044,9.7e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00062,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19090000,0.71,0.00051,-0.013,0.71,0.021,0.016,0.0018,0.012,0.0084,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0075,0.0052,-0.13,0.21,-4.4e-06,0.43,-0.00028,0.00066,3.4e-05,0,0,-3.6e+02,0.00011,0.0001,0.037,0.016,0.019,0.012,0.042,0.044,0.044,9.6e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.0006,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19190000,0.71,0.00056,-0.013,0.71,0.02,0.016,0.0019,0.012,0.0076,-3.7e+02,-0.0013,-0.0059,-2.7e-05,0.008,0.0054,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00067,3.7e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.043,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.00058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19290000,0.71,0.00058,-0.013,0.71,0.02,0.015,0.0046,0.013,0.0088,-3.7e+02,-0.0013,-0.0059,-3e-05,0.0078,0.0058,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00066,4e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.019,0.012,0.042,0.044,0.043,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19390000,0.71,0.00054,-0.013,0.71,0.019,0.014,0.0084,0.012,0.0079,-3.7e+02,-0.0013,-0.0059,-2.4e-05,0.0078,0.0056,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00065,3.5e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.014,0.017,0.011,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0054,0.0066,0.00054,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19490000,0.71,0.00056,-0.013,0.71,0.019,0.015,0.0049,0.014,0.01,-3.7e+02,-0.0013,-0.0058,-1.8e-05,0.0078,0.0049,-0.13,0.21,-4.6e-06,0.43,-0.00029,0.00066,3.8e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.018,0.011,0.042,0.044,0.043,8.8e-07,1.4e-06,2.1e-06,0.0054,0.0066,0.00052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19590000,0.71,0.00063,-0.013,0.71,0.017,0.015,0.0043,0.012,0.0095,-3.7e+02,-0.0013,-0.0058,-6.7e-06,0.0086,0.0047,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00068,4.7e-05,0,0,-3.6e+02,0.00011,9.8e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.5e-07,1.4e-06,2.1e-06,0.0053,0.0065,0.0005,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19690000,0.71,0.00067,-0.013,0.71,0.017,0.013,0.0059,0.013,0.01,-3.7e+02,-0.0013,-0.0059,-1e-05,0.0089,0.0053,-0.13,0.21,-5e-06,0.43,-0.00031,0.00068,3.9e-05,0,0,-3.6e+02,0.00011,9.8e-05,0.036,0.015,0.018,0.011,0.042,0.043,0.042,8.4e-07,1.4e-06,2.1e-06,0.0053,0.0064,0.00049,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19790000,0.71,0.00075,-0.013,0.71,0.014,0.011,0.0064,0.011,0.009,-3.7e+02,-0.0013,-0.0059,-5.6e-06,0.0094,0.0057,-0.13,0.21,-5.3e-06,0.43,-0.00031,0.00068,3.7e-05,0,0,-3.6e+02,0.00011,9.6e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00047,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19890000,0.71,0.00066,-0.013,0.71,0.015,0.013,0.0076,0.014,0.011,-3.7e+02,-0.0013,-0.0058,2.5e-06,0.0092,0.0046,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00069,4.5e-05,0,0,-3.6e+02,0.00011,9.6e-05,0.036,0.015,0.018,0.01,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0052,0.0063,0.00046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19990000,0.71,0.00063,-0.013,0.7,0.013,0.013,0.01,0.012,0.011,-3.7e+02,-0.0013,-0.0058,1.8e-05,0.0095,0.0038,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.0007,5e-05,0,0,-3.6e+02,0.0001,9.4e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00044,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -20090000,0.71,0.00066,-0.013,0.7,0.013,0.013,0.011,0.013,0.013,-3.7e+02,-0.0013,-0.0058,2.8e-05,0.01,0.0031,-0.13,0.21,-4.8e-06,0.43,-0.00032,0.00072,6.1e-05,0,0,-3.6e+02,0.00011,9.4e-05,0.036,0.014,0.018,0.01,0.041,0.043,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20190000,0.71,0.0007,-0.013,0.7,0.012,0.012,0.013,0.011,0.012,-3.7e+02,-0.0013,-0.0058,3.7e-05,0.0099,0.0028,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00072,6.1e-05,0,0,-3.6e+02,0.0001,9.2e-05,0.036,0.013,0.016,0.0098,0.037,0.039,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00042,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20290000,0.71,0.0007,-0.013,0.7,0.01,0.012,0.011,0.012,0.013,-3.7e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0027,-0.13,0.21,-4.8e-06,0.43,-0.00032,0.00074,6.2e-05,0,0,-3.6e+02,0.0001,9.2e-05,0.036,0.014,0.018,0.0097,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.006,0.0004,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20390000,0.71,0.00066,-0.013,0.7,0.0086,0.0097,0.013,0.01,0.012,-3.7e+02,-0.0013,-0.0058,4.5e-05,0.01,0.0028,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00073,5.2e-05,0,0,-3.6e+02,0.0001,9.1e-05,0.036,0.013,0.016,0.0095,0.037,0.039,0.04,7.3e-07,1.1e-06,2e-06,0.005,0.0059,0.00039,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20490000,0.71,0.00071,-0.013,0.7,0.0087,0.0097,0.013,0.011,0.012,-3.7e+02,-0.0013,-0.0058,4.2e-05,0.01,0.003,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00072,5.1e-05,0,0,-3.6e+02,0.0001,9.1e-05,0.036,0.014,0.017,0.0094,0.041,0.043,0.04,7.2e-07,1.1e-06,2e-06,0.005,0.0059,0.00038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20590000,0.71,0.00074,-0.013,0.7,0.0078,0.0076,0.0099,0.0091,0.01,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.01,0.0036,-0.13,0.21,-5e-06,0.43,-0.00031,0.00072,5e-05,0,0,-3.6e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0092,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0058,0.00037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20690000,0.71,0.00077,-0.013,0.7,0.0084,0.0077,0.011,0.01,0.011,-3.7e+02,-0.0013,-0.0058,4.6e-05,0.01,0.0034,-0.13,0.21,-5e-06,0.43,-0.00031,0.00072,5.2e-05,0,0,-3.6e+02,0.0001,8.9e-05,0.036,0.014,0.017,0.0092,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.0049,0.0058,0.00036,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20790000,0.71,0.00081,-0.013,0.7,0.0063,0.0072,0.012,0.0084,0.01,-3.7e+02,-0.0013,-0.0058,5.1e-05,0.011,0.0035,-0.13,0.21,-5e-06,0.43,-0.00032,0.00073,4.6e-05,0,0,-3.6e+02,9.8e-05,8.7e-05,0.036,0.013,0.016,0.009,0.037,0.039,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00035,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20890000,0.71,0.00082,-0.013,0.7,0.0062,0.0068,0.011,0.009,0.011,-3.7e+02,-0.0013,-0.0058,5.9e-05,0.011,0.0031,-0.13,0.21,-5e-06,0.43,-0.00033,0.00074,5.2e-05,0,0,-3.6e+02,9.8e-05,8.8e-05,0.036,0.014,0.017,0.0089,0.04,0.043,0.039,6.6e-07,1e-06,2e-06,0.0049,0.0057,0.00034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -20990000,0.71,0.00084,-0.013,0.7,0.0044,0.0045,0.011,0.009,0.01,-3.7e+02,-0.0013,-0.0058,6.3e-05,0.011,0.0033,-0.13,0.21,-5e-06,0.43,-0.00034,0.00075,4.9e-05,0,0,-3.6e+02,9.6e-05,8.6e-05,0.036,0.013,0.016,0.0087,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21090000,0.71,0.00081,-0.013,0.7,0.0054,0.0037,0.012,0.01,0.011,-3.7e+02,-0.0013,-0.0058,6.8e-05,0.011,0.0029,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00075,4.6e-05,0,0,-3.6e+02,9.7e-05,8.6e-05,0.036,0.014,0.017,0.0087,0.04,0.043,0.039,6.4e-07,9.8e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21190000,0.71,0.00082,-0.013,0.7,0.0057,0.0028,0.011,0.011,0.0091,-3.7e+02,-0.0013,-0.0058,6.8e-05,0.011,0.0031,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00075,4.3e-05,0,0,-3.6e+02,9.4e-05,8.4e-05,0.036,0.013,0.016,0.0085,0.037,0.039,0.039,6.2e-07,9.4e-07,1.9e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21290000,0.71,0.0009,-0.013,0.7,0.005,0.0029,0.013,0.011,0.01,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0026,-0.13,0.21,-4.9e-06,0.43,-0.00034,0.00077,4.7e-05,0,0,-3.6e+02,9.5e-05,8.5e-05,0.036,0.014,0.017,0.0084,0.04,0.043,0.038,6.2e-07,9.4e-07,1.9e-06,0.0048,0.0055,0.00031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21390000,0.71,0.00088,-0.013,0.7,0.004,0.00086,0.013,0.0095,0.0093,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.011,0.0028,-0.13,0.21,-5e-06,0.43,-0.00033,0.00076,4.7e-05,0,0,-3.6e+02,9.3e-05,8.3e-05,0.036,0.013,0.016,0.0083,0.037,0.039,0.038,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21490000,0.71,0.00088,-0.013,0.7,0.0045,0.0013,0.013,0.01,0.0098,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0024,-0.13,0.21,-5e-06,0.43,-0.00032,0.00077,5.3e-05,0,0,-3.6e+02,9.4e-05,8.3e-05,0.036,0.014,0.017,0.0082,0.04,0.043,0.038,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21590000,0.71,0.00087,-0.013,0.7,0.0033,0.0017,0.012,0.009,0.0091,-3.7e+02,-0.0013,-0.0058,7.7e-05,0.011,0.0025,-0.13,0.21,-5.1e-06,0.43,-0.00032,0.00076,5e-05,0,0,-3.6e+02,9.1e-05,8.2e-05,0.036,0.013,0.015,0.0081,0.037,0.039,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0053,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21690000,0.71,0.00084,-0.013,0.7,0.0049,0.0021,0.014,0.01,0.0097,-3.7e+02,-0.0013,-0.0058,8.1e-05,0.011,0.0021,-0.13,0.21,-5e-06,0.43,-0.00031,0.00077,5.1e-05,0,0,-3.6e+02,9.2e-05,8.2e-05,0.036,0.013,0.017,0.0081,0.04,0.042,0.038,5.8e-07,8.6e-07,1.9e-06,0.0047,0.0053,0.00028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21790000,0.71,0.00084,-0.013,0.7,0.003,0.0042,0.013,0.0074,0.01,-3.7e+02,-0.0013,-0.0058,7.2e-05,0.011,0.0023,-0.13,0.21,-5.6e-06,0.43,-0.00033,0.00076,5.3e-05,0,0,-3.6e+02,9e-05,8e-05,0.036,0.012,0.015,0.0079,0.036,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21890000,0.71,0.00083,-0.013,0.7,0.0038,0.0047,0.013,0.0079,0.011,-3.7e+02,-0.0013,-0.0058,7.3e-05,0.011,0.0022,-0.13,0.21,-5.5e-06,0.43,-0.00033,0.00076,5e-05,0,0,-3.6e+02,9.1e-05,8.1e-05,0.036,0.013,0.016,0.0079,0.04,0.042,0.037,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21990000,0.71,0.00085,-0.013,0.7,0.0026,0.0054,0.014,0.006,0.012,-3.7e+02,-0.0013,-0.0058,7e-05,0.012,0.002,-0.13,0.21,-5.9e-06,0.43,-0.00034,0.00076,5.2e-05,0,0,-3.7e+02,8.8e-05,7.9e-05,0.036,0.012,0.015,0.0077,0.036,0.038,0.037,5.4e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22090000,0.71,0.00088,-0.013,0.7,0.0025,0.007,0.012,0.006,0.013,-3.7e+02,-0.0013,-0.0058,7e-05,0.012,0.0021,-0.13,0.21,-5.9e-06,0.43,-0.00034,0.00076,5.2e-05,0,0,-3.7e+02,8.9e-05,7.9e-05,0.036,0.013,0.016,0.0077,0.04,0.042,0.037,5.4e-07,7.9e-07,1.8e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22190000,0.71,0.00085,-0.013,0.7,0.0019,0.007,0.013,0.0053,0.011,-3.7e+02,-0.0013,-0.0058,7.6e-05,0.012,0.0021,-0.13,0.21,-5.7e-06,0.43,-0.00035,0.00077,4.1e-05,0,0,-3.7e+02,8.7e-05,7.8e-05,0.036,0.012,0.015,0.0076,0.036,0.038,0.037,5.3e-07,7.6e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22290000,0.71,0.00088,-0.013,0.7,0.0013,0.0067,0.013,0.0057,0.012,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.012,0.0022,-0.13,0.21,-5.8e-06,0.43,-0.00035,0.00076,4.2e-05,0,0,-3.7e+02,8.8e-05,7.8e-05,0.036,0.013,0.016,0.0075,0.04,0.042,0.037,5.2e-07,7.6e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22390000,0.71,0.00089,-0.013,0.7,-0.001,0.0064,0.015,0.0041,0.01,-3.7e+02,-0.0013,-0.0058,8.1e-05,0.012,0.0024,-0.13,0.21,-5.7e-06,0.43,-0.00035,0.00077,4.3e-05,0,0,-3.7e+02,8.6e-05,7.7e-05,0.036,0.012,0.015,0.0074,0.036,0.038,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22490000,0.71,0.00093,-0.013,0.7,-0.0021,0.0072,0.016,0.0033,0.011,-3.7e+02,-0.0013,-0.0058,8.2e-05,0.012,0.0026,-0.13,0.21,-5.7e-06,0.43,-0.00037,0.00078,4.1e-05,0,0,-3.7e+02,8.6e-05,7.7e-05,0.036,0.013,0.016,0.0074,0.039,0.042,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22590000,0.71,0.00096,-0.013,0.7,-0.0038,0.0065,0.015,0.00096,0.01,-3.7e+02,-0.0014,-0.0058,8.5e-05,0.013,0.0027,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00079,3.8e-05,0,0,-3.7e+02,8.4e-05,7.5e-05,0.036,0.012,0.015,0.0073,0.036,0.038,0.036,5e-07,7.1e-07,1.8e-06,0.0044,0.0049,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22690000,0.71,0.001,-0.013,0.7,-0.0052,0.008,0.016,0.00022,0.012,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.013,0.0026,-0.13,0.21,-5.5e-06,0.43,-0.00039,0.0008,3.7e-05,0,0,-3.7e+02,8.5e-05,7.6e-05,0.036,0.013,0.016,0.0073,0.039,0.042,0.036,4.9e-07,7e-07,1.8e-06,0.0044,0.0049,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22790000,0.71,0.001,-0.013,0.7,-0.0071,0.0069,0.017,-0.0024,0.0091,-3.7e+02,-0.0014,-0.0058,8.1e-05,0.013,0.0034,-0.13,0.21,-5.7e-06,0.43,-0.00039,0.00078,4.3e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.012,0.015,0.0071,0.036,0.038,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22890000,0.71,0.00099,-0.013,0.7,-0.0076,0.0078,0.019,-0.0024,0.0098,-3.7e+02,-0.0014,-0.0058,8e-05,0.013,0.0033,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00077,3.9e-05,0,0,-3.7e+02,8.4e-05,7.5e-05,0.036,0.013,0.016,0.0071,0.039,0.042,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22990000,0.71,0.00097,-0.013,0.7,-0.0077,0.0068,0.02,-0.0036,0.009,-3.7e+02,-0.0014,-0.0058,9e-05,0.013,0.0032,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.00078,3.6e-05,0,0,-3.7e+02,8.2e-05,7.3e-05,0.036,0.012,0.015,0.007,0.036,0.038,0.036,4.7e-07,6.5e-07,1.7e-06,0.0043,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23090000,0.71,0.00092,-0.013,0.7,-0.0081,0.0067,0.02,-0.0043,0.009,-3.7e+02,-0.0014,-0.0058,8.1e-05,0.012,0.0034,-0.13,0.21,-5.5e-06,0.43,-0.00038,0.00077,3.3e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.013,0.016,0.007,0.039,0.042,0.036,4.6e-07,6.5e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23190000,0.71,0.00097,-0.013,0.7,-0.0094,0.0047,0.022,-0.0076,0.0078,-3.7e+02,-0.0014,-0.0058,8.4e-05,0.013,0.0036,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00076,2.5e-05,0,0,-3.7e+02,8.1e-05,7.2e-05,0.036,0.012,0.014,0.0069,0.036,0.038,0.035,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23290000,0.71,0.00089,-0.013,0.7,-0.0093,0.0042,0.022,-0.0081,0.0084,-3.7e+02,-0.0014,-0.0058,8.6e-05,0.012,0.0034,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00076,2.4e-05,0,0,-3.7e+02,8.1e-05,7.3e-05,0.036,0.013,0.016,0.0069,0.039,0.042,0.036,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0047,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23390000,0.71,0.00095,-0.013,0.7,-0.0095,0.003,0.02,-0.01,0.0072,-3.7e+02,-0.0014,-0.0058,8.8e-05,0.012,0.0035,-0.13,0.21,-5.6e-06,0.43,-0.00035,0.00075,2.6e-05,0,0,-3.7e+02,8e-05,7.1e-05,0.036,0.012,0.014,0.0068,0.036,0.038,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23490000,0.71,0.0033,-0.01,0.7,-0.016,0.0032,-0.013,-0.011,0.008,-3.7e+02,-0.0014,-0.0058,9.5e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00079,5.1e-05,0,0,-3.7e+02,8e-05,7.2e-05,0.036,0.013,0.015,0.0068,0.039,0.042,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 -23590000,0.71,0.0086,-0.0026,0.7,-0.027,0.0032,-0.045,-0.011,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00084,0.00012,0,0,-3.7e+02,7.8e-05,7.1e-05,0.036,0.012,0.014,0.0067,0.036,0.038,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0046,0.0002,0.0013,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23690000,0.71,0.0082,0.0032,0.71,-0.058,-0.0046,-0.095,-0.015,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00078,9e-05,0,0,-3.7e+02,7.9e-05,7.1e-05,0.036,0.013,0.015,0.0067,0.039,0.042,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23790000,0.71,0.0053,-0.00011,0.71,-0.083,-0.016,-0.15,-0.016,0.0069,-3.7e+02,-0.0013,-0.0058,9.3e-05,0.011,0.0028,-0.13,0.21,-4.7e-06,0.43,-0.00039,0.00078,0.00044,0,0,-3.7e+02,7.7e-05,7e-05,0.036,0.012,0.014,0.0066,0.036,0.038,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23890000,0.71,0.0026,-0.0062,0.71,-0.1,-0.025,-0.2,-0.026,0.0047,-3.7e+02,-0.0013,-0.0058,9.2e-05,0.012,0.0029,-0.13,0.21,-4.5e-06,0.43,-0.00042,0.00083,0.00035,0,0,-3.7e+02,7.8e-05,7e-05,0.036,0.013,0.016,0.0066,0.039,0.042,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23990000,0.71,0.0013,-0.011,0.71,-0.1,-0.029,-0.26,-0.031,0.00042,-3.7e+02,-0.0013,-0.0058,9.8e-05,0.012,0.0029,-0.13,0.21,-4.2e-06,0.43,-0.00039,0.00083,0.00032,0,0,-3.7e+02,7.7e-05,6.9e-05,0.036,0.012,0.015,0.0065,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24090000,0.71,0.0025,-0.0095,0.71,-0.1,-0.028,-0.3,-0.041,-0.002,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0026,-0.13,0.21,-3.8e-06,0.43,-0.00042,0.0008,0.00036,0,0,-3.7e+02,7.7e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24190000,0.71,0.0036,-0.0072,0.71,-0.11,-0.03,-0.35,-0.044,-0.0052,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0025,-0.13,0.21,-3e-06,0.43,-0.00042,0.00083,0.00036,0,0,-3.7e+02,7.6e-05,6.8e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,4e-07,5.3e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24290000,0.71,0.0041,-0.0064,0.71,-0.12,-0.033,-0.41,-0.055,-0.0085,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0025,-0.13,0.21,-2.7e-06,0.43,-0.00046,0.00088,0.00042,0,0,-3.7e+02,7.6e-05,6.8e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4e-07,5.3e-07,1.6e-06,0.0041,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24390000,0.71,0.0042,-0.0065,0.71,-0.13,-0.041,-0.46,-0.062,-0.021,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0031,-0.13,0.21,1.4e-07,0.43,-0.00034,0.00092,0.00042,0,0,-3.7e+02,7.5e-05,6.7e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24490000,0.71,0.005,-0.0024,0.71,-0.14,-0.046,-0.51,-0.076,-0.025,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0031,-0.13,0.21,1.4e-07,0.43,-0.00034,0.00093,0.00041,0,0,-3.7e+02,7.5e-05,6.7e-05,0.036,0.013,0.016,0.0064,0.039,0.042,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24590000,0.71,0.0055,0.0013,0.71,-0.16,-0.057,-0.56,-0.081,-0.035,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.0031,-0.13,0.21,1.2e-06,0.43,1.8e-05,0.00058,0.00036,0,0,-3.7e+02,7.4e-05,6.6e-05,0.036,0.012,0.015,0.0063,0.036,0.038,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24690000,0.71,0.0056,0.0022,0.71,-0.18,-0.07,-0.64,-0.097,-0.041,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.0029,-0.13,0.21,2.2e-06,0.43,-2.7e-05,0.00062,0.00054,0,0,-3.7e+02,7.4e-05,6.7e-05,0.036,0.013,0.016,0.0063,0.039,0.042,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24790000,0.71,0.0053,0.00098,0.71,-0.2,-0.083,-0.73,-0.11,-0.054,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.003,-0.13,0.21,1.6e-06,0.43,5.7e-06,0.00059,0.0003,0,0,-3.7e+02,7.3e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24890000,0.71,0.0071,0.0027,0.71,-0.22,-0.094,-0.75,-0.13,-0.063,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.0031,-0.13,0.21,2.4e-06,0.43,-0.0001,0.00075,0.00032,0,0,-3.7e+02,7.4e-05,6.6e-05,0.036,0.013,0.016,0.0062,0.039,0.042,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24990000,0.71,0.0089,0.0044,0.71,-0.24,-0.1,-0.81,-0.13,-0.073,-3.7e+02,-0.0013,-0.0058,0.00011,0.0098,0.0027,-0.13,0.21,2e-06,0.43,-0.00018,0.00085,-2e-05,0,0,-3.7e+02,7.2e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.7e-07,1.5e-06,0.0041,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25090000,0.71,0.0092,0.0038,0.71,-0.27,-0.11,-0.86,-0.16,-0.084,-3.7e+02,-0.0013,-0.0058,0.00011,0.0098,0.0028,-0.13,0.21,1.5e-06,0.43,-0.0002,0.00086,-5.6e-05,0,0,-3.7e+02,7.3e-05,6.5e-05,0.036,0.013,0.017,0.0062,0.039,0.042,0.033,3.7e-07,4.7e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25190000,0.71,0.0087,0.0024,0.71,-0.3,-0.13,-0.91,-0.18,-0.11,-3.7e+02,-0.0013,-0.0058,0.00013,0.0092,0.0031,-0.13,0.21,6.9e-06,0.43,5.9e-05,0.00083,8e-05,0,0,-3.7e+02,7.1e-05,6.4e-05,0.035,0.012,0.016,0.0061,0.036,0.038,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25290000,0.71,0.011,0.0093,0.71,-0.33,-0.14,-0.96,-0.21,-0.12,-3.7e+02,-0.0013,-0.0058,0.00013,0.0092,0.0031,-0.13,0.21,6.8e-06,0.43,8.4e-05,0.00077,8.7e-05,0,0,-3.7e+02,7.2e-05,6.4e-05,0.035,0.013,0.017,0.0061,0.039,0.042,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25390000,0.71,0.012,0.016,0.71,-0.36,-0.16,-1,-0.22,-0.14,-3.7e+02,-0.0013,-0.0058,0.00014,0.0084,0.0029,-0.13,0.21,1.1e-05,0.43,0.00049,0.00046,0.00012,0,0,-3.7e+02,7.1e-05,6.3e-05,0.035,0.012,0.016,0.006,0.036,0.038,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25490000,0.71,0.012,0.017,0.71,-0.41,-0.18,-1.1,-0.26,-0.16,-3.7e+02,-0.0013,-0.0058,0.00014,0.0084,0.0027,-0.13,0.21,9.5e-06,0.43,0.00066,0.00013,0.00031,0,0,-3.7e+02,7.2e-05,6.4e-05,0.035,0.013,0.018,0.006,0.039,0.042,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25590000,0.71,0.012,0.015,0.71,-0.45,-0.21,-1.1,-0.29,-0.2,-3.7e+02,-0.0012,-0.0058,0.00016,0.0077,0.0031,-0.13,0.21,1.6e-05,0.43,0.00096,0.00014,0.00032,0,0,-3.7e+02,7e-05,6.3e-05,0.034,0.012,0.018,0.006,0.036,0.038,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0042,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25690000,0.71,0.015,0.022,0.71,-0.5,-0.23,-1.2,-0.34,-0.22,-3.7e+02,-0.0012,-0.0058,0.00016,0.0077,0.0031,-0.13,0.21,1.6e-05,0.43,0.00095,0.00016,0.0004,0,0,-3.7e+02,7.1e-05,6.3e-05,0.034,0.013,0.02,0.006,0.039,0.042,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0042,0.00015,0.0012,3.9e-05,0.0012,0.0014,0.0012,0.0011,1,1,0.01 -25790000,0.71,0.018,0.028,0.71,-0.54,-0.26,-1.2,-0.36,-0.25,-3.7e+02,-0.0012,-0.0058,0.00016,0.007,0.0024,-0.13,0.21,1.9e-05,0.43,0.0013,-8.9e-05,-4.9e-05,0,0,-3.7e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.0059,0.036,0.038,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 -25890000,0.71,0.018,0.029,0.71,-0.62,-0.29,-1.3,-0.41,-0.28,-3.7e+02,-0.0012,-0.0058,0.00017,0.0072,0.0024,-0.13,0.21,2.1e-05,0.43,0.0014,-2.1e-05,-0.00011,0,0,-3.7e+02,7.1e-05,6.2e-05,0.033,0.014,0.022,0.006,0.039,0.042,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 -25990000,0.7,0.017,0.026,0.71,-0.67,-0.32,-1.3,-0.45,-0.33,-3.7e+02,-0.0012,-0.0058,0.00019,0.0063,0.0027,-0.13,0.21,2.9e-05,0.43,0.0023,-0.00058,-0.00057,0,0,-3.7e+02,7e-05,6.1e-05,0.032,0.013,0.021,0.0059,0.036,0.039,0.033,3.4e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 -26090000,0.7,0.022,0.035,0.71,-0.74,-0.35,-1.3,-0.53,-0.37,-3.7e+02,-0.0012,-0.0059,0.00018,0.0064,0.0029,-0.13,0.21,2.5e-05,0.43,0.0024,-0.0005,-0.0012,0,0,-3.7e+02,7.1e-05,6.2e-05,0.032,0.014,0.024,0.0059,0.039,0.043,0.033,3.4e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 -26190000,0.7,0.024,0.045,0.71,-0.79,-0.39,-1.3,-0.55,-0.41,-3.7e+02,-0.0012,-0.0058,0.00018,0.0053,0.0017,-0.13,0.21,3.9e-05,0.43,0.0023,0.00039,-0.0014,0,0,-3.7e+02,7e-05,6.1e-05,0.03,0.014,0.024,0.0058,0.036,0.039,0.032,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.001,0.0013,0.001,0.001,1,1,0.01 -26290000,0.7,0.025,0.047,0.71,-0.89,-0.43,-1.3,-0.64,-0.45,-3.7e+02,-0.0012,-0.0058,0.00018,0.0052,0.0018,-0.13,0.21,3.8e-05,0.43,0.0023,0.00027,-0.0014,0,0,-3.7e+02,7.1e-05,6.1e-05,0.03,0.015,0.028,0.0059,0.039,0.043,0.033,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.00099,3.9e-05,0.00099,0.0013,0.001,0.00099,1,1,0.01 -26390000,0.7,0.024,0.044,0.71,-0.96,-0.49,-1.3,-0.7,-0.54,-3.7e+02,-0.0011,-0.0059,0.00021,0.0044,0.0025,-0.13,0.21,4.6e-05,0.44,0.0036,-0.00019,-0.0024,0,0,-3.7e+02,7.1e-05,6e-05,0.028,0.014,0.027,0.0058,0.036,0.039,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00014,0.00096,3.9e-05,0.00095,0.0012,0.00096,0.00095,1,1,0.01 -26490000,0.7,0.031,0.06,0.71,-1.1,-0.53,-1.3,-0.8,-0.59,-3.7e+02,-0.0011,-0.0059,0.00021,0.0044,0.0025,-0.13,0.21,3.9e-05,0.44,0.004,-0.001,-0.0026,0,0,-3.7e+02,7.1e-05,6.1e-05,0.028,0.016,0.031,0.0058,0.039,0.044,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00014,0.00092,3.9e-05,0.00092,0.0012,0.00092,0.00091,1,1,0.01 -26590000,0.7,0.037,0.076,0.71,-1.2,-0.59,-1.3,-0.85,-0.66,-3.7e+02,-0.0011,-0.0059,0.00019,0.0028,0.0015,-0.13,0.21,3.9e-05,0.44,0.0041,-0.00065,-0.0048,0,0,-3.7e+02,7.1e-05,6e-05,0.025,0.015,0.031,0.0058,0.036,0.04,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00087,3.9e-05,0.00086,0.001,0.00087,0.00086,1,1,0.01 -26690000,0.7,0.039,0.079,0.71,-1.3,-0.65,-1.3,-0.97,-0.72,-3.7e+02,-0.0011,-0.0059,0.00019,0.0028,0.0014,-0.13,0.21,4.5e-05,0.44,0.004,-0.00014,-0.004,0,0,-3.7e+02,7.2e-05,6.1e-05,0.025,0.017,0.038,0.0058,0.04,0.045,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00081,3.9e-05,0.0008,0.001,0.00081,0.00079,1,1,0.01 -26790000,0.7,0.036,0.074,0.71,-1.4,-0.74,-1.3,-1.1,-0.85,-3.7e+02,-0.0011,-0.0059,0.00022,0.0012,0.0023,-0.13,0.21,8.4e-05,0.44,0.0055,0.00061,-0.0037,0,0,-3.7e+02,7.2e-05,6e-05,0.022,0.016,0.036,0.0057,0.036,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00076,3.9e-05,0.00075,0.00092,0.00076,0.00074,1,1,0.01 -26890000,0.7,0.045,0.096,0.71,-1.6,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.0011,-0.0059,0.00023,0.0013,0.0023,-0.13,0.21,8.9e-05,0.44,0.0054,0.0012,-0.0041,0,0,-3.7e+02,7.3e-05,6e-05,0.022,0.018,0.043,0.0058,0.04,0.046,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00072,3.9e-05,0.0007,0.00092,0.00072,0.0007,1,1,0.01 -26990000,0.7,0.051,0.12,0.71,-1.7,-0.89,-1.3,-1.3,-1,-3.7e+02,-0.00099,-0.0059,0.00022,-0.00068,0.00038,-0.13,0.21,0.00013,0.44,0.0061,0.0034,-0.0056,0,0,-3.7e+02,7.3e-05,5.9e-05,0.019,0.017,0.042,0.0057,0.037,0.041,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00065,3.9e-05,0.00063,0.00079,0.00065,0.00062,1,1,0.01 -27090000,0.7,0.052,0.12,0.71,-1.9,-0.98,-1.3,-1.5,-1.1,-3.7e+02,-0.00099,-0.0059,0.00022,-0.00072,0.00039,-0.13,0.21,0.00013,0.44,0.006,0.0035,-0.0052,0,0,-3.7e+02,7.4e-05,6e-05,0.019,0.02,0.052,0.0057,0.04,0.048,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00059,3.9e-05,0.00056,0.00078,0.0006,0.00056,1,1,0.01 -27190000,0.7,0.05,0.11,0.7,-2.1,-1,-1.2,-1.7,-1.2,-3.7e+02,-0.00097,-0.0059,0.00022,-0.0018,0.0002,-0.13,0.21,4.8e-05,0.44,0.0021,0.0027,-0.0049,0,0,-3.7e+02,7.5e-05,6e-05,0.016,0.02,0.051,0.0057,0.043,0.05,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00055,3.9e-05,0.00051,0.00066,0.00055,0.00051,1,1,0.01 -27290000,0.71,0.044,0.095,0.7,-2.3,-1.1,-1.2,-1.9,-1.3,-3.7e+02,-0.00097,-0.0059,0.00023,-0.0018,0.00019,-0.13,0.21,5.6e-05,0.44,0.0019,0.0034,-0.0049,0,0,-3.7e+02,7.5e-05,6e-05,0.016,0.022,0.059,0.0057,0.047,0.057,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00052,3.9e-05,0.00048,0.00066,0.00052,0.00048,1,1,0.01 -27390000,0.71,0.038,0.079,0.7,-2.4,-1.1,-1.2,-2.1,-1.4,-3.7e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0016,-0.13,0.21,1.3e-05,0.44,-0.0005,0.0031,-0.0063,0,0,-3.7e+02,7.6e-05,6e-05,0.013,0.021,0.052,0.0057,0.049,0.059,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00049,3.9e-05,0.00046,0.00055,0.00049,0.00046,1,1,0.01 -27490000,0.71,0.032,0.064,0.7,-2.5,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00092,-0.0058,0.00022,-0.0029,-0.0015,-0.13,0.21,1.9e-05,0.44,-0.00058,0.0032,-0.0067,0,0,-3.7e+02,7.7e-05,6.1e-05,0.013,0.023,0.056,0.0057,0.054,0.067,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00048,3.9e-05,0.00045,0.00055,0.00048,0.00044,1,1,0.01 -27590000,0.72,0.028,0.051,0.69,-2.6,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.00092,-0.0059,0.00023,-0.0036,-0.00088,-0.12,0.21,-3.7e-05,0.44,-0.0032,0.0027,-0.0065,0,0,-3.7e+02,7.7e-05,6e-05,0.011,0.021,0.047,0.0057,0.056,0.068,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00044,1,1,0.01 -27690000,0.72,0.027,0.05,0.69,-2.6,-1.2,-1.2,-2.9,-1.7,-3.7e+02,-0.00092,-0.0059,0.00023,-0.0036,-0.00075,-0.12,0.21,-3.2e-05,0.44,-0.0033,0.0026,-0.0067,0,0,-3.7e+02,7.8e-05,6.1e-05,0.011,0.022,0.049,0.0057,0.062,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00043,1,1,0.01 -27790000,0.72,0.027,0.051,0.69,-2.6,-1.2,-1.2,-3.1,-1.8,-3.7e+02,-0.00092,-0.0059,0.00022,-0.0042,-0.00056,-0.12,0.21,-6e-05,0.44,-0.005,0.0021,-0.0072,0,0,-3.7e+02,7.8e-05,6e-05,0.0097,0.02,0.042,0.0056,0.064,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00045,3.9e-05,0.00043,0.00041,0.00045,0.00043,1,1,0.01 -27890000,0.72,0.027,0.049,0.69,-2.7,-1.2,-1.2,-3.4,-1.9,-3.7e+02,-0.00091,-0.0059,0.00023,-0.0042,-0.00056,-0.12,0.21,-6.1e-05,0.44,-0.005,0.002,-0.0072,0,0,-3.7e+02,7.9e-05,6.1e-05,0.0097,0.021,0.043,0.0057,0.07,0.087,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00044,3.9e-05,0.00043,0.00041,0.00044,0.00042,1,1,0.01 -27990000,0.72,0.026,0.046,0.69,-2.7,-1.2,-1.2,-3.7,-2,-3.7e+02,-0.00093,-0.0059,0.00024,-0.004,0.00035,-0.12,0.21,-7.7e-05,0.44,-0.0063,0.0015,-0.0071,0,0,-3.7e+02,8e-05,6e-05,0.0086,0.02,0.038,0.0056,0.072,0.087,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00043,3.9e-05,0.00042,0.00037,0.00043,0.00042,1,1,0.01 -28090000,0.72,0.032,0.059,0.69,-2.8,-1.2,-1.2,-4,-2.1,-3.7e+02,-0.00093,-0.0059,0.00023,-0.0041,0.00056,-0.12,0.21,-7.6e-05,0.44,-0.0065,0.0013,-0.0072,0,0,-3.7e+02,8e-05,6.1e-05,0.0086,0.021,0.039,0.0057,0.078,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00042,3.9e-05,0.00042,0.00036,0.00042,0.00041,1,1,0.01 -28190000,0.72,0.037,0.072,0.69,-2.8,-1.2,-0.94,-4.3,-2.2,-3.7e+02,-0.00094,-0.0059,0.00024,-0.0042,0.001,-0.12,0.21,-9.4e-05,0.44,-0.0073,0.00091,-0.0071,0,0,-3.7e+02,8.1e-05,6.1e-05,0.0079,0.02,0.034,0.0056,0.08,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00041,3.9e-05,0.00041,0.00033,0.00041,0.00041,1,1,0.01 -28290000,0.72,0.029,0.055,0.69,-2.8,-1.2,-0.078,-4.5,-2.4,-3.7e+02,-0.00094,-0.0059,0.00024,-0.0043,0.0011,-0.12,0.21,-9.7e-05,0.44,-0.0073,0.0013,-0.0069,0,0,-3.7e+02,8.2e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.087,0.11,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28390000,0.73,0.012,0.024,0.69,-2.8,-1.2,0.78,-4.8,-2.5,-3.7e+02,-0.00094,-0.0059,0.00023,-0.0042,0.0014,-0.12,0.21,-8.5e-05,0.44,-0.0075,0.0014,-0.007,0,0,-3.7e+02,8.3e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.094,0.12,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28490000,0.73,0.0028,0.0061,0.69,-2.8,-1.2,1.1,-5.1,-2.6,-3.7e+02,-0.00095,-0.0059,0.00023,-0.0038,0.0017,-0.12,0.21,-6.6e-05,0.44,-0.0076,0.0014,-0.0069,0,0,-3.7e+02,8.3e-05,6.2e-05,0.0079,0.021,0.035,0.0057,0.1,0.13,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28590000,0.73,0.00089,0.0025,0.69,-2.7,-1.2,0.97,-5.4,-2.7,-3.7e+02,-0.00095,-0.0059,0.00024,-0.0039,0.0017,-0.12,0.21,-6.9e-05,0.44,-0.0075,0.0015,-0.0069,0,0,-3.7e+02,8.4e-05,6.2e-05,0.0079,0.021,0.033,0.0057,0.11,0.14,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28690000,0.73,0.00019,0.0016,0.69,-2.6,-1.2,0.98,-5.7,-2.8,-3.7e+02,-0.00095,-0.0059,0.00024,-0.0036,0.0021,-0.12,0.21,-5.2e-05,0.44,-0.0076,0.0014,-0.0068,0,0,-3.7e+02,8.5e-05,6.2e-05,0.0079,0.022,0.033,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.00039,0.0004,1,1,0.01 -28790000,0.73,-8.8e-06,0.0015,0.69,-2.6,-1.2,0.98,-6,-2.9,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0031,0.0023,-0.12,0.21,-9.2e-05,0.44,-0.009,0.00063,-0.006,0,0,-3.7e+02,8.5e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 -28890000,0.73,1.1e-06,0.0018,0.69,-2.5,-1.2,0.97,-6.2,-3,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0029,0.0026,-0.12,0.21,-7.6e-05,0.44,-0.0091,0.00059,-0.0059,0,0,-3.7e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.13,0.16,0.032,3.1e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 -28990000,0.73,0.00035,0.0024,0.68,-2.5,-1.1,0.97,-6.6,-3.1,-3.7e+02,-0.001,-0.0059,0.00025,-0.0016,0.003,-0.12,0.21,-0.00011,0.44,-0.01,-0.00033,-0.0047,0,0,-3.7e+02,8.7e-05,6.1e-05,0.0073,0.02,0.025,0.0056,0.13,0.16,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00039,0.00039,1,1,0.01 -29090000,0.73,0.00052,0.0028,0.68,-2.4,-1.1,0.96,-6.8,-3.3,-3.7e+02,-0.001,-0.0059,0.00025,-0.0014,0.0034,-0.12,0.21,-9.3e-05,0.44,-0.011,-0.00039,-0.0046,0,0,-3.7e+02,8.7e-05,6.2e-05,0.0073,0.021,0.025,0.0057,0.14,0.17,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29190000,0.73,0.00077,0.0032,0.68,-2.4,-1.1,0.95,-7.1,-3.4,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00099,0.0034,-0.12,0.21,-0.00013,0.44,-0.011,-0.00062,-0.0041,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0072,0.02,0.023,0.0056,0.14,0.17,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29290000,0.73,0.0011,0.004,0.68,-2.3,-1.1,0.98,-7.3,-3.5,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00096,0.0039,-0.12,0.21,-0.00012,0.44,-0.011,-0.00069,-0.0041,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0072,0.021,0.024,0.0056,0.14,0.18,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29390000,0.73,0.0017,0.0055,0.68,-2.3,-1.1,0.99,-7.6,-3.6,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00023,0.0044,-0.12,0.21,-0.00015,0.44,-0.012,-0.0014,-0.0033,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.18,0.031,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 -29490000,0.73,0.0023,0.0066,0.68,-2.3,-1.1,0.99,-7.9,-3.7,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00022,0.0046,-0.12,0.21,-0.00015,0.44,-0.012,-0.0013,-0.0033,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.15,0.19,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 -29590000,0.73,0.0027,0.0076,0.68,-2.2,-1.1,0.98,-8.1,-3.8,-3.7e+02,-0.0011,-0.0059,0.00026,0.0004,0.0046,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.19,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00038,1,1,0.01 -29690000,0.73,0.003,0.0082,0.68,-2.2,-1.1,0.98,-8.3,-3.9,-3.7e+02,-0.0011,-0.0059,0.00026,0.00033,0.005,-0.12,0.21,-0.00015,0.44,-0.012,-0.0016,-0.0029,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29790000,0.73,0.0034,0.0087,0.68,-2.2,-1.1,0.96,-8.6,-4,-3.7e+02,-0.0012,-0.0059,0.00025,0.0014,0.0048,-0.12,0.21,-0.00017,0.44,-0.012,-0.0019,-0.0023,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29890000,0.73,0.0034,0.0088,0.68,-2.1,-1.1,0.95,-8.8,-4.1,-3.7e+02,-0.0012,-0.0059,0.00025,0.0011,0.0053,-0.12,0.21,-0.00018,0.44,-0.013,-0.0019,-0.0023,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.17,0.21,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29990000,0.73,0.0036,0.0089,0.68,-2.1,-1.1,0.94,-9.1,-4.2,-3.7e+02,-0.0012,-0.0059,0.00022,0.0016,0.005,-0.12,0.21,-0.00019,0.44,-0.013,-0.0021,-0.002,0,0,-3.7e+02,8.8e-05,6e-05,0.0071,0.02,0.024,0.0056,0.17,0.21,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -30090000,0.73,0.0035,0.0088,0.68,-2.1,-1.1,0.92,-9.3,-4.3,-3.7e+02,-0.0012,-0.0059,0.00022,0.0012,0.0053,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.18,0.22,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -30190000,0.73,0.0036,0.0085,0.68,-2.1,-1.1,0.91,-9.5,-4.4,-3.7e+02,-0.0012,-0.0059,0.00021,0.0021,0.0047,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-3.7e+02,8.8e-05,6e-05,0.007,0.02,0.025,0.0055,0.18,0.22,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00037,0.00038,1,1,0.01 -30290000,0.73,0.0035,0.0083,0.68,-2,-1.1,0.9,-9.7,-4.5,-3.7e+02,-0.0012,-0.0059,0.00021,0.0019,0.005,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-3.7e+02,8.8e-05,6e-05,0.007,0.021,0.026,0.0056,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30390000,0.73,0.0035,0.008,0.68,-2,-1.1,0.89,-10,-4.6,-3.7e+02,-0.0012,-0.0059,0.00019,0.0026,0.0048,-0.12,0.21,-0.00022,0.43,-0.012,-0.0025,-0.0014,0,0,-3.7e+02,8.7e-05,6e-05,0.007,0.021,0.025,0.0055,0.19,0.23,0.031,2.8e-07,3.5e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30490000,0.73,0.0034,0.0077,0.68,-2,-1.1,0.87,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.00019,0.0026,0.005,-0.12,0.21,-0.00022,0.43,-0.012,-0.0024,-0.0014,0,0,-3.7e+02,8.7e-05,6e-05,0.007,0.022,0.027,0.0056,0.2,0.24,0.031,2.8e-07,3.5e-07,1.2e-06,0.0038,0.0039,9.8e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30590000,0.73,0.0034,0.0073,0.68,-1.9,-1,0.83,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00018,0.0034,0.0046,-0.12,0.21,-0.00024,0.43,-0.012,-0.0025,-0.001,0,0,-3.7e+02,8.6e-05,6e-05,0.0069,0.021,0.026,0.0055,0.2,0.24,0.031,2.8e-07,3.5e-07,1.1e-06,0.0037,0.0038,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30690000,0.73,0.0031,0.0069,0.68,-1.9,-1,0.83,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00018,0.0032,0.0049,-0.12,0.21,-0.00024,0.43,-0.012,-0.0024,-0.001,0,0,-3.7e+02,8.6e-05,6e-05,0.0069,0.022,0.028,0.0055,0.21,0.25,0.031,2.8e-07,3.5e-07,1.1e-06,0.0037,0.0038,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30790000,0.73,0.0031,0.0065,0.68,-1.9,-1,0.82,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00015,0.0039,0.0043,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00078,0,0,-3.7e+02,8.4e-05,6e-05,0.0068,0.021,0.027,0.0055,0.21,0.25,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30890000,0.73,0.0029,0.006,0.68,-1.9,-1,0.81,-11,-5.1,-3.7e+02,-0.0013,-0.0059,0.00015,0.0039,0.0047,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00076,0,0,-3.7e+02,8.5e-05,6e-05,0.0068,0.022,0.029,0.0055,0.22,0.26,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30990000,0.73,0.003,0.0054,0.68,-1.8,-1,0.8,-11,-5.2,-3.7e+02,-0.0013,-0.0058,0.00012,0.0048,0.0042,-0.12,0.21,-0.00025,0.43,-0.011,-0.0027,-0.00042,0,0,-3.7e+02,8.3e-05,5.9e-05,0.0067,0.021,0.028,0.0055,0.22,0.26,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.5e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31090000,0.73,0.0027,0.0049,0.68,-1.8,-1,0.79,-11,-5.3,-3.7e+02,-0.0013,-0.0058,0.00012,0.0046,0.0046,-0.12,0.21,-0.00026,0.43,-0.011,-0.0027,-0.00042,0,0,-3.7e+02,8.3e-05,6e-05,0.0067,0.022,0.03,0.0055,0.23,0.27,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31190000,0.73,0.0026,0.0044,0.68,-1.8,-1,0.78,-12,-5.3,-3.7e+02,-0.0013,-0.0058,9.7e-05,0.0049,0.0045,-0.12,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00025,0,0,-3.7e+02,8.1e-05,5.9e-05,0.0066,0.021,0.028,0.0055,0.23,0.27,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31290000,0.73,0.0023,0.0039,0.68,-1.8,-1,0.78,-12,-5.4,-3.7e+02,-0.0013,-0.0058,0.0001,0.0046,0.0049,-0.11,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00028,0,0,-3.7e+02,8.2e-05,5.9e-05,0.0066,0.022,0.03,0.0055,0.24,0.28,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.3e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31390000,0.73,0.0022,0.0032,0.68,-1.7,-0.99,0.78,-12,-5.5,-3.7e+02,-0.0013,-0.0058,7.8e-05,0.0051,0.0047,-0.11,0.21,-0.0003,0.43,-0.011,-0.0028,-2.8e-05,0,0,-3.7e+02,7.9e-05,5.9e-05,0.0065,0.021,0.029,0.0054,0.24,0.28,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 -31490000,0.73,0.0019,0.0026,0.68,-1.7,-0.99,0.78,-12,-5.6,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.005,0.0052,-0.11,0.21,-0.0003,0.43,-0.011,-0.0029,9.1e-06,0,0,-3.7e+02,8e-05,5.9e-05,0.0065,0.022,0.031,0.0055,0.25,0.29,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 -31590000,0.73,0.002,0.0021,0.68,-1.7,-0.97,0.77,-12,-5.7,-3.7e+02,-0.0013,-0.0058,4.7e-05,0.0059,0.0048,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00025,0,0,-3.7e+02,7.7e-05,5.9e-05,0.0063,0.021,0.029,0.0054,0.25,0.29,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31690000,0.73,0.0016,0.0014,0.68,-1.6,-0.97,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,4.9e-05,0.0056,0.0052,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00021,0,0,-3.7e+02,7.8e-05,5.9e-05,0.0063,0.022,0.031,0.0054,0.26,0.3,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31790000,0.73,0.0015,0.00057,0.69,-1.6,-0.95,0.78,-13,-5.9,-3.7e+02,-0.0013,-0.0058,2.4e-05,0.0066,0.0051,-0.11,0.21,-0.0003,0.43,-0.0097,-0.0029,0.00055,0,0,-3.7e+02,7.6e-05,5.9e-05,0.0062,0.021,0.029,0.0054,0.26,0.3,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31890000,0.73,0.0013,-0.00016,0.69,-1.6,-0.95,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,2.5e-05,0.0065,0.0056,-0.11,0.21,-0.00029,0.43,-0.0097,-0.0029,0.00058,0,0,-3.7e+02,7.6e-05,5.9e-05,0.0062,0.022,0.031,0.0054,0.27,0.31,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31990000,0.73,0.0012,-0.00077,0.69,-1.6,-0.93,0.77,-13,-6.1,-3.7e+02,-0.0013,-0.0058,-6.6e-06,0.007,0.0054,-0.11,0.21,-0.00029,0.43,-0.0092,-0.003,0.00075,0,0,-3.7e+02,7.4e-05,5.8e-05,0.006,0.021,0.03,0.0054,0.27,0.31,0.031,2.6e-07,2.9e-07,9.8e-07,0.0036,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32090000,0.73,0.00083,-0.0015,0.69,-1.5,-0.93,0.78,-13,-6.2,-3.7e+02,-0.0013,-0.0058,-7.5e-06,0.0068,0.0059,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00076,0,0,-3.7e+02,7.5e-05,5.9e-05,0.006,0.022,0.032,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.8e-07,0.0036,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32190000,0.73,0.00062,-0.0025,0.69,-1.5,-0.91,0.78,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-4.2e-05,0.0073,0.006,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-3.7e+02,7.2e-05,5.8e-05,0.0059,0.021,0.03,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32290000,0.73,0.00035,-0.0032,0.69,-1.5,-0.91,0.77,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-4.1e-05,0.0071,0.0065,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-3.7e+02,7.3e-05,5.8e-05,0.0059,0.022,0.032,0.0054,0.29,0.33,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32390000,0.73,0.00025,-0.004,0.69,-1.5,-0.89,0.77,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-5.9e-05,0.0076,0.0064,-0.11,0.2,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-3.7e+02,7.1e-05,5.8e-05,0.0057,0.021,0.03,0.0054,0.29,0.33,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00036,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32490000,0.72,0.0001,-0.0042,0.69,-1.4,-0.88,0.78,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-5.7e-05,0.0074,0.0069,-0.11,0.21,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-3.7e+02,7.1e-05,5.8e-05,0.0057,0.022,0.032,0.0054,0.3,0.34,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32590000,0.72,0.00015,-0.0046,0.69,-1.4,-0.87,0.78,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-7.8e-05,0.0078,0.0068,-0.11,0.21,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-3.7e+02,7e-05,5.8e-05,0.0056,0.021,0.03,0.0053,0.3,0.34,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32690000,0.72,0.00011,-0.0046,0.69,-1.4,-0.86,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-7.9e-05,0.0078,0.0072,-0.11,0.2,-0.0003,0.43,-0.008,-0.0031,0.0014,0,0,-3.7e+02,7e-05,5.8e-05,0.0056,0.022,0.032,0.0053,0.31,0.35,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00036,1,1,0.01 -32790000,0.72,0.00023,-0.0047,0.69,-1.3,-0.84,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-9.9e-05,0.0081,0.0072,-0.11,0.21,-0.0003,0.43,-0.0076,-0.0031,0.0015,0,0,-3.7e+02,6.8e-05,5.7e-05,0.0054,0.021,0.03,0.0053,0.3,0.35,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -32890000,0.72,0.00031,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00011,0.008,0.0078,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0032,0.0016,0,0,-3.7e+02,6.9e-05,5.8e-05,0.0054,0.022,0.031,0.0053,0.32,0.36,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -32990000,0.72,0.00052,-0.0047,0.69,-1.3,-0.82,0.77,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0085,0.008,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-3.7e+02,6.7e-05,5.7e-05,0.0052,0.021,0.029,0.0053,0.31,0.36,0.03,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -33090000,0.72,0.00049,-0.0047,0.69,-1.3,-0.82,0.76,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0084,0.0083,-0.11,0.21,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-3.7e+02,6.7e-05,5.7e-05,0.0053,0.022,0.031,0.0053,0.33,0.37,0.031,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -33190000,0.72,0.0039,-0.0039,0.7,-1.2,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00012,0.0085,0.0082,-0.11,0.21,-0.0003,0.43,-0.0068,-0.0031,0.0017,0,0,-3.7e+02,6.6e-05,5.7e-05,0.0051,0.022,0.029,0.0053,0.32,0.37,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0035,8.4e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 -33290000,0.67,0.016,-0.0033,0.74,-1.2,-0.78,0.68,-15,-7.1,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0083,0.0084,-0.11,0.2,-0.00028,0.43,-0.007,-0.0032,0.0016,0,0,-3.7e+02,6.6e-05,5.7e-05,0.0051,0.022,0.031,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0035,8.3e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 -33390000,0.56,0.014,-0.0037,0.83,-1.2,-0.77,0.88,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00013,0.0085,0.0087,-0.11,0.21,-0.00034,0.43,-0.0063,-0.0032,0.0018,0,0,-3.7e+02,6.5e-05,5.6e-05,0.0047,0.021,0.028,0.0053,0.33,0.38,0.031,2.4e-07,2.6e-07,8.3e-07,0.0036,0.0035,8.3e-05,0.00032,3.8e-05,0.00036,0.00021,0.00032,0.00036,1,1,0.01 -33490000,0.43,0.007,-0.0011,0.9,-1.2,-0.76,0.89,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00014,0.0085,0.0088,-0.11,0.21,-0.00042,0.43,-0.0058,-0.002,0.0018,0,0,-3.7e+02,6.5e-05,5.6e-05,0.0041,0.022,0.029,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.1e-07,0.0036,0.0035,8.3e-05,0.00025,3.7e-05,0.00036,0.00017,0.00024,0.00036,1,1,0.01 -33590000,0.27,0.00094,-0.0036,0.96,-1.2,-0.75,0.86,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00018,0.0085,0.0088,-0.11,0.21,-0.00067,0.43,-0.0038,-0.0013,0.002,0,0,-3.7e+02,6.4e-05,5.5e-05,0.0031,0.02,0.027,0.0052,0.34,0.37,0.03,2.4e-07,2.6e-07,7.9e-07,0.0036,0.0035,8.3e-05,0.00016,3.6e-05,0.00036,0.00012,0.00015,0.00036,1,1,0.01 -33690000,0.098,-0.0027,-0.0066,1,-1.1,-0.74,0.87,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00019,0.0085,0.0088,-0.11,0.21,-0.00072,0.43,-0.0035,-0.001,0.002,0,0,-3.7e+02,6.4e-05,5.5e-05,0.0024,0.021,0.028,0.0053,0.35,0.37,0.031,2.4e-07,2.6e-07,7.8e-07,0.0036,0.0035,8.3e-05,0.0001,3.5e-05,0.00036,8.3e-05,9.8e-05,0.00036,1,1,0.01 -33790000,-0.074,-0.0045,-0.0084,1,-1.1,-0.72,0.85,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00021,0.0085,0.0088,-0.11,0.21,-0.00088,0.43,-0.0021,-0.001,0.0023,0,0,-3.7e+02,6.2e-05,5.4e-05,0.0019,0.02,0.026,0.0052,0.35,0.37,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,6.8e-05,3.5e-05,0.00036,5.5e-05,6.1e-05,0.00036,1,1,0.01 -33890000,-0.24,-0.0059,-0.009,0.97,-1,-0.69,0.83,-16,-7.6,-3.7e+02,-0.0014,-0.0057,-0.00021,0.0085,0.0088,-0.11,0.21,-0.001,0.43,-0.0012,-0.0011,0.0024,0,0,-3.7e+02,6.2e-05,5.4e-05,0.0016,0.022,0.028,0.0052,0.36,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,4.8e-05,3.4e-05,0.00036,3.8e-05,4.1e-05,0.00036,1,1,0.01 -33990000,-0.39,-0.0046,-0.012,0.92,-0.94,-0.64,0.8,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0085,0.0089,-0.11,0.21,-0.00097,0.43,-0.0011,-0.00064,0.0025,0,0,-3.7e+02,6e-05,5.3e-05,0.0015,0.021,0.027,0.0052,0.36,0.37,0.03,2.4e-07,2.5e-07,7.7e-07,0.0036,0.0035,8.3e-05,3.6e-05,3.4e-05,0.00036,2.8e-05,2.9e-05,0.00036,1,1,0.01 -34090000,-0.5,-0.0037,-0.014,0.87,-0.88,-0.59,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0085,0.0092,-0.11,0.21,-0.00095,0.43,-0.0012,-0.00052,0.0025,0,0,-3.7e+02,6e-05,5.3e-05,0.0014,0.023,0.03,0.0052,0.37,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,3e-05,3.4e-05,0.00036,2.2e-05,2.3e-05,0.00036,1,1,0.01 -34190000,-0.57,-0.0036,-0.012,0.82,-0.86,-0.54,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00021,0.0063,0.012,-0.11,0.21,-0.00094,0.43,-0.001,-0.00031,0.0027,0,0,-3.7e+02,5.7e-05,5.1e-05,0.0013,0.023,0.029,0.0052,0.37,0.38,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.5e-05,3.4e-05,0.00036,1.8e-05,1.8e-05,0.00036,1,1,0.01 -34290000,-0.61,-0.0046,-0.0091,0.79,-0.8,-0.48,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.0002,0.0061,0.012,-0.11,0.21,-0.00096,0.43,-0.00092,-0.00018,0.0027,0,0,-3.7e+02,5.7e-05,5.1e-05,0.0012,0.025,0.032,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.2e-05,3.4e-05,0.00036,1.5e-05,1.5e-05,0.00036,1,1,0.01 -34390000,-0.63,-0.0052,-0.0062,0.77,-0.77,-0.44,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00018,0.0033,0.016,-0.11,0.21,-0.00092,0.43,-0.00091,1.6e-05,0.0029,0,0,-3.7e+02,5.3e-05,4.9e-05,0.0012,0.025,0.031,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,2e-05,3.3e-05,0.00036,1.3e-05,1.3e-05,0.00036,1,1,0.01 -34490000,-0.65,-0.0062,-0.004,0.76,-0.72,-0.39,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00018,0.0031,0.017,-0.11,0.21,-0.00093,0.43,-0.00085,-2.5e-05,0.0029,0,0,-3.7e+02,5.3e-05,4.9e-05,0.0011,0.027,0.035,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.1e-05,1.8e-05,3.3e-05,0.00036,1.2e-05,1.2e-05,0.00036,1,1,0.01 -34590000,-0.66,-0.0062,-0.0026,0.75,-0.7,-0.37,0.8,-16,-8,-3.7e+02,-0.0015,-0.0058,-0.00015,-0.0018,0.023,-0.11,0.21,-0.00088,0.43,-0.00092,3e-05,0.0032,0,0,-3.7e+02,5e-05,4.7e-05,0.0011,0.027,0.034,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,1.1e-05,1e-05,0.00036,1,1,0.01 -34690000,-0.67,-0.0066,-0.0018,0.75,-0.64,-0.32,0.8,-17,-8.1,-3.7e+02,-0.0015,-0.0058,-0.00015,-0.0021,0.023,-0.11,0.21,-0.0009,0.43,-0.00078,0.00023,0.0031,0,0,-3.7e+02,5e-05,4.7e-05,0.0011,0.03,0.037,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,9.9e-06,9.4e-06,0.00036,1,1,0.01 -34790000,-0.67,-0.006,-0.0013,0.74,-0.63,-0.3,0.79,-17,-8.1,-3.7e+02,-0.0015,-0.0058,-0.00011,-0.008,0.03,-0.11,0.21,-0.00089,0.43,-0.00062,0.00032,0.0032,0,0,-3.7e+02,4.6e-05,4.4e-05,0.001,0.029,0.036,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,9.1e-06,8.6e-06,0.00036,1,1,0.01 -34890000,-0.67,-0.006,-0.0012,0.74,-0.57,-0.26,0.79,-17,-8.2,-3.7e+02,-0.0015,-0.0058,-0.00011,-0.0081,0.03,-0.11,0.21,-0.00089,0.43,-0.00063,0.00028,0.0033,0,0,-3.7e+02,4.6e-05,4.4e-05,0.001,0.032,0.04,0.0052,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,8.4e-06,7.9e-06,0.00036,1,1,0.01 -34990000,-0.67,-0.013,-0.0037,0.74,0.47,0.35,-0.043,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-6.7e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00051,0.00034,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.001,0.034,0.046,0.0054,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.3e-05,3.3e-05,0.00036,8e-06,7.4e-06,0.00036,1,1,0.01 -35090000,-0.67,-0.013,-0.0037,0.74,0.6,0.39,-0.1,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-6.9e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00047,0.00028,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00099,0.037,0.051,0.0055,0.42,0.43,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.2e-05,3.3e-05,0.00036,7.5e-06,6.9e-06,0.00036,1,1,0.01 -35190000,-0.67,-0.013,-0.0038,0.74,0.63,0.43,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-6.9e-05,-0.016,0.039,-0.11,0.21,-0.00088,0.43,-0.00041,0.00032,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00099,0.041,0.055,0.0055,0.43,0.44,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.2e-05,3.3e-05,0.00036,7.1e-06,6.4e-06,0.00036,1,1,0.01 -35290000,-0.67,-0.013,-0.0038,0.74,0.66,0.47,-0.099,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-7.1e-05,-0.016,0.039,-0.11,0.21,-0.00089,0.43,-0.00033,0.00032,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00098,0.044,0.06,0.0055,0.44,0.45,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.8e-06,6.1e-06,0.00036,1,1,0.01 -35390000,-0.67,-0.013,-0.0038,0.74,0.69,0.51,-0.096,-17,-8,-3.7e+02,-0.0016,-0.0058,-7.3e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00023,0.00029,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00098,0.048,0.064,0.0055,0.46,0.47,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.5e-06,5.8e-06,0.00036,1,1,0.01 -35490000,-0.67,-0.013,-0.0038,0.74,0.73,0.56,-0.095,-17,-8,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00014,0.00024,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.053,0.069,0.0055,0.47,0.48,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.2e-06,5.5e-06,0.00036,1,1,0.01 -35590000,-0.67,-0.013,-0.0038,0.74,0.76,0.6,-0.094,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.5e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00017,0.00025,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.057,0.075,0.0055,0.49,0.5,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6e-06,5.2e-06,0.00036,1,1,0.01 -35690000,-0.67,-0.013,-0.0038,0.74,0.79,0.64,-0.092,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-9.2e-05,0.00024,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.062,0.08,0.0056,0.51,0.52,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.8e-06,5e-06,0.00036,1,1,0.01 -35790000,-0.67,-0.013,-0.0038,0.74,0.82,0.68,-0.089,-16,-7.8,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-6.7e-05,0.00023,0.0036,0,0,-3.7e+02,4.2e-05,4.2e-05,0.00097,0.067,0.086,0.0056,0.53,0.54,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.6e-06,4.8e-06,0.00036,1,1,0.023 -35890000,-0.67,-0.013,-0.0038,0.74,0.85,0.72,-0.086,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-5.2e-05,0.00022,0.0037,0,0,-3.7e+02,4.2e-05,4.2e-05,0.00097,0.072,0.092,0.0056,0.55,0.56,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.4e-06,4.6e-06,0.00036,1,1,0.048 -35990000,-0.67,-0.013,-0.0038,0.74,0.88,0.76,-0.083,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-7.7e-05,0.00021,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.078,0.098,0.0056,0.57,0.59,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.8e-06,3.3e-05,0.00036,5.3e-06,4.5e-06,0.00036,1,1,0.073 -36090000,-0.68,-0.013,-0.0038,0.74,0.91,0.81,-0.079,-16,-7.6,-3.7e+02,-0.0016,-0.0058,-7.9e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-4.2e-05,0.00019,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.083,0.11,0.0056,0.6,0.62,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.7e-06,3.3e-05,0.00036,5.2e-06,4.3e-06,0.00036,1,1,0.099 -36190000,-0.68,-0.013,-0.0038,0.74,0.94,0.85,-0.075,-16,-7.5,-3.7e+02,-0.0016,-0.0058,-8.3e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,5.5e-05,0.00018,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.089,0.11,0.0056,0.63,0.65,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.5e-06,3.3e-05,0.00036,5e-06,4.2e-06,0.00036,1,1,0.12 -36290000,-0.68,-0.013,-0.0038,0.74,0.97,0.89,-0.07,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,7.5e-05,0.00018,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.095,0.12,0.0056,0.66,0.68,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.4e-06,3.3e-05,0.00036,4.9e-06,4.1e-06,0.00036,1,1,0.15 -36390000,-0.68,-0.013,-0.0038,0.74,1,0.93,-0.067,-16,-7.3,-3.7e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,7.3e-05,0.00022,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.1,0.13,0.0056,0.69,0.72,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.3e-06,3.3e-05,0.00036,4.8e-06,3.9e-06,0.00036,1,1,0.17 -36490000,-0.68,-0.013,-0.0038,0.74,1,0.97,-0.063,-16,-7.2,-3.7e+02,-0.0016,-0.0058,-8.3e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,4.3e-05,0.00023,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.11,0.13,0.0056,0.72,0.76,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.2e-06,3.3e-05,0.00036,4.7e-06,3.8e-06,0.00036,1,1,0.2 -36590000,-0.68,-0.013,-0.0038,0.74,1.1,1,-0.057,-16,-7.1,-3.7e+02,-0.0016,-0.0058,-8.5e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,9.1e-05,0.00025,0.0037,0,0,-3.7e+02,4.3e-05,4.3e-05,0.00096,0.12,0.14,0.0056,0.76,0.8,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.1e-06,3.3e-05,0.00036,4.6e-06,3.7e-06,0.00036,1,1,0.23 -36690000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.053,-15,-7,-3.7e+02,-0.0016,-0.0058,-8.7e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,0.00012,0.00026,0.0037,0,0,-3.7e+02,4.3e-05,4.3e-05,0.00096,0.12,0.15,0.0057,0.8,0.84,0.032,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9e-06,3.3e-05,0.00036,4.6e-06,3.6e-06,0.00036,1,1,0.25 -36790000,-0.68,-0.013,-0.0037,0.74,1.1,1.1,-0.047,-15,-6.9,-3.7e+02,-0.0016,-0.0058,-9.1e-05,-0.015,0.038,-0.11,0.21,-0.00097,0.43,0.00017,0.00022,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.13,0.16,0.0057,0.84,0.9,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.9e-06,3.3e-05,0.00036,4.5e-06,3.5e-06,0.00036,1,1,0.28 -36890000,-0.68,-0.013,-0.0037,0.74,1.2,1.1,-0.042,-15,-6.8,-3.7e+02,-0.0016,-0.0058,-9.4e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00021,0.00022,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.14,0.17,0.0056,0.89,0.95,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.8e-06,3.3e-05,0.00036,4.4e-06,3.4e-06,0.00035,1,1,0.3 -36990000,-0.68,-0.013,-0.0037,0.74,1.2,1.2,-0.037,-15,-6.7,-3.7e+02,-0.0016,-0.0058,-9.5e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00023,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,0.94,1,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.7e-06,3.3e-05,0.00036,4.3e-06,3.4e-06,0.00035,1,1,0.33 -37090000,-0.68,-0.013,-0.0036,0.74,1.2,1.2,-0.031,-15,-6.6,-3.7e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.6e-06,3.3e-05,0.00036,4.3e-06,3.3e-06,0.00035,1,1,0.35 -37190000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.025,-15,-6.4,-3.7e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.16,0.19,0.0057,1.1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.38 -37290000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.02,-15,-6.3,-3.7e+02,-0.0016,-0.0058,-9.7e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00024,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.4e-05,0.00096,0.17,0.2,0.0057,1.1,1.2,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.41 -37390000,-0.68,-0.013,-0.0036,0.74,1.3,1.4,-0.015,-15,-6.2,-3.7e+02,-0.0016,-0.0058,-9.9e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00027,0.00027,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.18,0.21,0.0057,1.2,1.3,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3.1e-06,0.00035,1,1,0.43 -37490000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0093,-14,-6,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.001,0.43,0.0003,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.19,0.22,0.0057,1.3,1.4,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.3e-06,3.3e-05,0.00036,4.1e-06,3e-06,0.00035,1,1,0.46 -37590000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0027,-14,-5.9,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00032,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.2,0.23,0.0057,1.3,1.5,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.3e-06,3.3e-05,0.00036,4e-06,3e-06,0.00035,1,1,0.48 -37690000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,0.0046,-14,-5.7,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00033,0.00029,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.21,0.24,0.0057,1.4,1.6,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.51 -37790000,-0.68,-0.013,-0.0036,0.74,1.5,1.5,0.012,-14,-5.6,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00034,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.22,0.25,0.0056,1.5,1.7,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.54 -37890000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.017,-14,-5.4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-3.7e+02,4.5e-05,4.5e-05,0.00096,0.23,0.27,0.0056,1.6,1.8,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.56 -37990000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.025,-14,-5.3,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.24,0.28,0.0056,1.7,1.9,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.59 -38090000,-0.68,-0.013,-0.0036,0.74,1.5,1.7,0.034,-14,-5.1,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00037,0.00029,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.25,0.29,0.0056,1.8,2,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.61 -38190000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.04,-13,-4.9,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0038,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.26,0.3,0.0056,1.9,2.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.64 -38290000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.046,-13,-4.7,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00027,0.0038,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.27,0.31,0.0056,2.1,2.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.67 -38390000,-0.68,-0.013,-0.0035,0.74,1.6,1.8,0.052,-13,-4.6,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.28,0.32,0.0056,2.2,2.5,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.69 -38490000,-0.68,-0.013,-0.0035,0.74,1.7,1.8,0.058,-13,-4.4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00031,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00096,0.29,0.34,0.0056,2.3,2.6,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.72 -38590000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.063,-13,-4.2,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00032,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.3,0.35,0.0056,2.5,2.8,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.6e-06,0.00035,1,1,0.75 -38690000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.069,-13,-4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00039,0.00034,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.31,0.36,0.0056,2.6,3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.77 -38790000,-0.68,-0.013,-0.0034,0.74,1.8,1.9,0.075,-12,-3.8,-3.7e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00033,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.33,0.38,0.0056,2.8,3.1,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.8 -38890000,-0.68,-0.014,-0.0035,0.74,1.8,2,0.57,-12,-3.6,-3.7e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.0003,0.0037,0,0,-3.7e+02,4.8e-05,4.7e-05,0.00097,0.33,0.39,0.0056,3,3.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.7e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.83 +10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,0,0,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.032 +90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,0,0,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.058 +190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,0,0,-1.2e+02,-3e-11,-2.6e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.082 +290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,0,0,-1.2e+02,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,-1.2e+02,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.11 +390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0,0,-1.2e+02,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,-1.2e+02,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.13 +490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0,0,-1.2e+02,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,-1.2e+02,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.16 +590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0,0,-1.2e+02,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,-1.2e+02,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.18 +690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0,0,-1.2e+02,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,-1.2e+02,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.21 +790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0,0,-1.2e+02,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.018,0.018,0.00077,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.23 +890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0,0,-1.2e+02,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.019,0.019,0.00051,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.26 +990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0,0,-1.2e+02,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.021,0.021,0.00062,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.28 +1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0,0,-1.2e+02,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.023,0.023,0.00043,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.31 +1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0,0,-1.2e+02,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 +1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0,0,-1.2e+02,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 +1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0,0,-1.2e+02,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 +1490000,1,-0.01,-0.014,0.00016,0.024,0.0029,-0.16,0,0,-1.2e+02,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0,0,-1.2e+02,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.011,-0.014,0.00013,0.028,-0.00014,-0.19,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.011,-0.014,9.8e-05,0.035,-0.002,-0.2,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.011,-0.015,7.8e-05,0.043,-0.0033,-0.22,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,8.9e-05,0.036,-0.0048,-0.23,0,0,-1.2e+02,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,5.1e-05,0.041,-0.0073,-0.24,0,0,-1.2e+02,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,6.4e-05,0.033,-0.007,-0.26,0,0,-1.2e+02,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,5.1e-05,0.039,-0.0095,-0.27,0,0,-1.2e+02,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,6.9e-05,0.03,-0.0089,-0.29,0,0,-1.2e+02,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.013,5.1e-05,0.035,-0.011,-0.3,0,0,-1.2e+02,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.011,-0.013,6.6e-05,0.026,-0.0093,-0.31,0,0,-1.2e+02,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.011,-0.013,6.3e-05,0.03,-0.011,-0.33,0,0,-1.2e+02,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.011,-0.013,5.8e-05,0.023,-0.0096,-0.34,0,0,-1.2e+02,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.011,-0.013,8.3e-06,0.027,-0.012,-0.35,0,0,-1.2e+02,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.011,-0.013,5.6e-05,0.022,-0.0098,-0.36,0,0,-1.2e+02,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.011,-0.013,6e-05,0.025,-0.011,-0.38,0,0,-1.2e+02,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.011,-0.013,2.9e-06,0.02,-0.009,-0.39,0,0,-1.2e+02,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.011,-0.013,4.4e-05,0.023,-0.011,-0.4,0,0,-1.2e+02,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.011,-0.012,1.5e-05,0.018,-0.0095,-0.42,0,0,-1.2e+02,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.011,-0.013,8.2e-06,0.022,-0.012,-0.43,0,0,-1.2e+02,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.011,-0.012,3.2e-05,0.017,-0.011,-0.44,0,0,-1.2e+02,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.011,-0.012,0.00015,0.019,-0.014,-0.46,0,0,-1.2e+02,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.011,-0.012,0.0002,0.016,-0.014,-0.47,0,0,-1.2e+02,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.48,0,0,-1.2e+02,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.011,-0.012,0.00017,0.02,-0.017,-0.5,0,0,-1.2e+02,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.51,0,0,-1.2e+02,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.011,-0.012,0.00014,0.02,-0.017,-0.53,0,0,-1.2e+02,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.01,-0.012,9.8e-05,0.017,-0.012,-0.54,0,0,-1.2e+02,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.01,-0.012,0.00012,0.018,-0.013,-0.55,0,0,-1.2e+02,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.01,-0.012,0.00018,0.014,-0.01,-0.57,0,0,-1.2e+02,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.01,-0.012,0.00021,0.017,-0.012,-0.58,0,0,-1.2e+02,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.01,-0.012,0.00021,0.014,-0.01,-0.6,0,0,-1.2e+02,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.01,-0.012,0.0002,0.015,-0.012,-0.61,0,0,-1.2e+02,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.01,-0.011,0.00019,0.012,-0.01,-0.63,0,0,-1.2e+02,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.01,-0.012,0.00017,0.015,-0.011,-0.64,0,0,-1.2e+02,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.01,-0.011,0.00022,0.011,-0.0085,-0.66,0,0,-1.2e+02,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.01,-0.011,0.00024,0.013,-0.0098,-0.67,0,0,-1.2e+02,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.01,-0.011,0.00023,0.0086,-0.0073,-0.68,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0099,-0.011,0.00029,0.0081,-0.0081,-0.7,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0098,-0.011,0.0003,0.0055,-0.0062,-0.71,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0097,-0.011,0.00028,0.0061,-0.0066,-0.73,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0096,-0.011,0.00036,0.0041,-0.0038,-0.74,0,0,-1.2e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0095,-0.011,0.00035,0.0044,-0.0028,-0.75,0,0,-1.2e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0095,-0.011,0.00033,0.0038,-0.00092,0.0028,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0094,-0.011,0.00036,0.0041,0.00056,0.015,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-4.9e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0094,-0.011,0.00034,0.0051,0.0017,-0.011,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-4.9e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0094,-0.011,0.00027,0.0038,0.0042,-0.005,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0094,-0.011,0.00024,0.005,0.0043,-0.012,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-4.9e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0093,-0.011,0.00026,0.0043,0.0053,-0.05,0,0,-4.9e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-4.9e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0093,-0.011,0.00026,0.0049,0.0055,-0.052,0,0,-4.9e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0093,-0.011,0.00019,0.0037,0.0055,-0.099,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0093,-0.011,0.00012,0.0046,0.0051,-0.076,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6790000,0.71,0.0012,-0.014,0.71,0.0049,0.0051,-0.11,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,-6.9e-05,0.21,8e-05,0.43,3.6e-05,0.00032,-0.0024,0,0,-4.9e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.11,0.11,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 +6890000,0.71,0.0013,-0.014,0.7,0.00053,0.0064,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,-9.7e-05,0.21,1.3e-05,0.43,1.3e-06,0.00089,-0.00086,0,0,-4.9e+02,0.0013,0.0013,0.047,0.21,0.21,0.46,0.13,0.14,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 +6990000,0.71,0.0013,-0.014,0.71,-0.00023,0.0046,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.6e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.044,0.23,0.24,0.36,0.17,0.17,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7090000,0.71,0.0012,-0.014,0.71,-0.00079,0.0011,-0.13,0,0,-4.9e+02,-0.0014,-0.0057,-7.7e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00037,0.00025,-0.00041,0,0,-4.9e+02,0.0013,0.0013,0.043,0.27,0.27,0.29,0.2,0.21,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7190000,0.71,0.0013,-0.014,0.71,-0.0025,0.0019,-0.15,0,0,-4.9e+02,-0.0015,-0.0057,-7.7e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-4.9e+02,0.0013,0.0013,0.042,0.3,0.31,0.24,0.25,0.25,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 +7290000,0.71,0.0015,-0.014,0.71,-0.0044,0.0099,-0.15,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00021,-0.0002,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00039,0,0,-4.9e+02,0.0013,0.0013,0.042,0.34,0.35,0.2,0.3,0.31,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7390000,0.71,0.0016,-0.014,0.71,-0.0037,0.015,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00028,-3.8e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00032,0,0,-4.9e+02,0.0013,0.0013,0.041,0.38,0.39,0.18,0.37,0.37,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7490000,0.71,0.0015,-0.014,0.71,-0.0038,0.011,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00018,-7.3e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00078,-0.00043,0,0,-4.9e+02,0.0013,0.0013,0.041,0.43,0.43,0.15,0.44,0.45,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7590000,0.71,0.0016,-0.014,0.71,-0.0034,0.02,-0.17,0,0,-4.9e+02,-0.0017,-0.0057,-6.8e-05,-0.00024,0.00021,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-4.9e+02,0.0013,0.0013,0.04,0.48,0.48,0.14,0.53,0.53,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7690000,0.71,0.0016,-0.014,0.71,-0.0046,0.017,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00032,0.00084,-0.00033,0,0,-4.9e+02,0.0014,0.0013,0.04,0.53,0.53,0.13,0.63,0.63,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 +7790000,0.71,0.0017,-0.014,0.71,-0.011,0.016,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00036,6.2e-05,-0.0071,0.21,-1.6e-05,0.43,-0.00034,0.00078,-0.00038,0,0,-4.9e+02,0.0014,0.0013,0.04,0.58,0.58,0.12,0.74,0.74,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 +7890000,0.71,0.0017,-0.014,0.71,-0.011,0.021,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00038,0.0002,-0.0096,0.21,-1.5e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-4.9e+02,0.0014,0.0014,0.04,0.64,0.63,0.11,0.87,0.86,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 +7990000,0.71,0.0017,-0.014,0.71,-0.0091,0.022,-0.16,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00037,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00086,-0.00038,0,0,-4.9e+02,0.0014,0.0014,0.04,0.7,0.68,0.1,1,0.99,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 +8090000,0.71,0.0017,-0.014,0.71,-0.005,0.024,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-6.7e-05,-0.0003,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00033,0.0009,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.04,0.76,0.74,0.1,1.2,1.1,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8190000,0.71,0.0017,-0.014,0.71,-0.014,0.028,-0.18,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00043,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-4.9e+02,0.0014,0.0014,0.04,0.82,0.79,0.099,1.4,1.3,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8290000,0.71,0.0017,-0.014,0.71,-0.017,0.021,-0.17,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00056,0.00031,-0.017,0.21,-1e-05,0.43,-0.00031,0.00079,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.039,0.88,0.84,0.097,1.6,1.5,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8390000,0.71,0.0017,-0.014,0.71,-0.0012,0.00041,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.021,0.21,-9.3e-06,0.43,-0.0003,0.00084,-0.00031,0,0,-4.9e+02,0.0014,0.0014,0.039,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,7e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8490000,0.71,0.0017,-0.014,0.71,-0.003,0.0023,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.025,0.21,-9e-06,0.43,-0.00031,0.0008,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.089,6.2e-05,6.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8590000,0.71,0.0021,-0.014,0.71,-0.00044,0.00093,-0.17,0,0,-4.9e+02,-0.0018,-0.0057,-6.8e-05,-0.00051,0.00039,-0.029,0.21,-1.2e-05,0.43,-0.00042,0.00076,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.088,6e-05,6.8e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8690000,0.71,0.002,-0.014,0.71,-0.0034,0.0028,-0.16,0,0,-4.9e+02,-0.0017,-0.0056,-6.6e-05,-0.00051,0.00039,-0.035,0.21,-1e-05,0.43,-0.00039,0.00084,-0.00029,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.088,5.8e-05,6.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8790000,0.71,0.0019,-0.014,0.71,-0.0057,0.0049,-0.15,0,0,-4.9e+02,-0.0017,-0.0057,-6.9e-05,-0.0005,0.00043,-0.041,0.21,-9.1e-06,0.43,-0.00037,0.0008,-0.00029,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.087,5.6e-05,6.6e-05,2.4e-06,0.04,0.04,0.032,0.0013,6.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8890000,0.71,0.0019,-0.014,0.71,-0.0079,0.0055,-0.15,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00063,0.00042,-0.045,0.21,-7.8e-06,0.43,-0.00034,0.00078,-0.00033,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.086,5.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.03,0.0013,6.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +8990000,0.71,0.0018,-0.014,0.71,-0.01,0.0049,-0.14,0,0,-4.9e+02,-0.0015,-0.0058,-7.5e-05,-0.00087,0.00044,-0.051,0.21,-6.6e-06,0.43,-0.0003,0.00071,-0.00034,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.087,5.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.029,0.0013,6.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9090000,0.71,0.002,-0.014,0.71,-0.014,0.006,-0.14,0,0,-4.9e+02,-0.0016,-0.0058,-7.6e-05,-0.00098,0.00054,-0.053,0.21,-6.9e-06,0.43,-0.00033,0.00068,-0.00034,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1.1e+02,1.1e+02,0.086,4.9e-05,6.2e-05,2.4e-06,0.04,0.04,0.028,0.0013,5.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9190000,0.71,0.0019,-0.014,0.71,-0.012,0.0087,-0.14,0,0,-4.9e+02,-0.0015,-0.0056,-7e-05,-0.00086,0.00059,-0.057,0.21,-6.2e-06,0.43,-0.00031,0.00081,-0.00025,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.094,1.1e+02,1.1e+02,0.085,4.6e-05,6e-05,2.4e-06,0.04,0.04,0.027,0.0013,5.6e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9290000,0.71,0.0017,-0.014,0.71,-0.011,0.0086,-0.14,0,0,-4.9e+02,-0.0015,-0.0056,-7.1e-05,-0.00096,0.00059,-0.061,0.21,-5.1e-06,0.43,-0.00026,0.00082,-0.00024,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.093,1.1e+02,1.1e+02,0.085,4.4e-05,5.8e-05,2.4e-06,0.04,0.04,0.025,0.0013,5.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9390000,0.71,0.0015,-0.014,0.71,-0.011,0.0092,-0.14,0,0,-4.9e+02,-0.0014,-0.0056,-7.3e-05,-0.001,0.00058,-0.065,0.21,-4.3e-06,0.43,-0.00022,0.00082,-0.00022,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.093,1.2e+02,1.2e+02,0.086,4.2e-05,5.7e-05,2.4e-06,0.04,0.04,0.024,0.0013,5.2e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9490000,0.71,0.0014,-0.014,0.71,-0.0078,0.011,-0.13,0,0,-4.9e+02,-0.0014,-0.0055,-6.9e-05,-0.001,0.0006,-0.068,0.21,-3.7e-06,0.43,-0.00018,0.0009,-0.00013,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.091,1.2e+02,1.2e+02,0.085,4e-05,5.5e-05,2.4e-06,0.04,0.04,0.023,0.0013,5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9590000,0.71,0.0016,-0.014,0.71,-0.01,0.016,-0.13,0,0,-4.9e+02,-0.0015,-0.0054,-6.6e-05,-0.0011,0.00079,-0.072,0.21,-4.5e-06,0.43,-0.00024,0.00091,-0.00012,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.09,1.3e+02,1.3e+02,0.085,3.8e-05,5.4e-05,2.4e-06,0.04,0.04,0.021,0.0013,4.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9690000,0.71,0.0018,-0.014,0.71,-0.017,0.017,-0.12,0,0,-4.9e+02,-0.0015,-0.0056,-7e-05,-0.0013,0.00092,-0.077,0.21,-4.8e-06,0.43,-0.00027,0.0008,-0.00017,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.089,1.3e+02,1.3e+02,0.086,3.6e-05,5.2e-05,2.4e-06,0.04,0.04,0.02,0.0013,4.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9790000,0.71,0.0017,-0.014,0.71,-0.013,0.02,-0.11,0,0,-4.9e+02,-0.0015,-0.0055,-6.8e-05,-0.0014,0.001,-0.082,0.21,-4.4e-06,0.43,-0.00024,0.00085,-9.7e-05,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.087,1.4e+02,1.4e+02,0.085,3.4e-05,5e-05,2.4e-06,0.04,0.04,0.019,0.0013,4.5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9890000,0.71,0.0018,-0.014,0.71,-0.016,0.023,-0.11,0,0,-4.9e+02,-0.0015,-0.0055,-6.8e-05,-0.0015,0.0011,-0.085,0.21,-4.6e-06,0.43,-0.00026,0.00083,-0.0001,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.084,1.4e+02,1.4e+02,0.085,3.2e-05,4.9e-05,2.4e-06,0.04,0.04,0.018,0.0013,4.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9990000,0.71,0.0019,-0.014,0.71,-0.02,0.021,-0.1,0,0,-4.9e+02,-0.0015,-0.0056,-7.1e-05,-0.0016,0.0011,-0.089,0.21,-4.2e-06,0.43,-0.00025,0.00078,-0.00013,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.083,1.5e+02,1.5e+02,0.086,3e-05,4.7e-05,2.4e-06,0.04,0.04,0.017,0.0013,4.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +10090000,0.71,0.002,-0.014,0.71,-0.022,0.025,-0.096,0,0,-4.9e+02,-0.0015,-0.0056,-6.9e-05,-0.0017,0.0013,-0.091,0.21,-4.6e-06,0.43,-0.00029,0.00079,-0.00012,0,0,-4.9e+02,0.0013,0.0012,0.039,25,25,0.08,1.6e+02,1.6e+02,0.085,2.9e-05,4.6e-05,2.4e-06,0.04,0.04,0.016,0.0013,4.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10190000,0.71,0.002,-0.013,0.71,-0.033,0.022,-0.096,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,-0.0019,0.0013,-0.093,0.21,-4.5e-06,0.43,-0.00027,0.00065,-0.00015,0,0,-4.9e+02,0.0012,0.0012,0.039,25,25,0.078,1.7e+02,1.7e+02,0.084,2.7e-05,4.4e-05,2.4e-06,0.04,0.04,0.014,0.0013,4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10290000,0.71,0.002,-0.013,0.71,-0.04,0.017,-0.084,0,0,-4.9e+02,-0.0015,-0.0058,-7.8e-05,-0.0021,0.0014,-0.098,0.21,-4.2e-06,0.43,-0.00026,0.00058,-0.00017,0,0,-4.9e+02,0.0012,0.0012,0.039,25,25,0.076,1.8e+02,1.8e+02,0.085,2.6e-05,4.2e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10390000,0.71,0.0018,-0.013,0.71,0.0091,-0.02,0.0093,0,0,-4.9e+02,-0.0015,-0.0058,-7.9e-05,-0.0021,0.0013,-0.098,0.21,-3.7e-06,0.43,-0.00023,0.0006,-0.00014,0,0,-4.9e+02,0.0012,0.0012,0.039,0.25,0.25,0.56,0.5,0.5,0.077,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10490000,0.71,0.0018,-0.013,0.71,0.0071,-0.019,0.022,0,0,-4.9e+02,-0.0014,-0.0059,-8.3e-05,-0.0022,0.0013,-0.098,0.21,-3.3e-06,0.43,-0.00021,0.00053,-0.00016,0,0,-4.9e+02,0.0012,0.0012,0.039,0.26,0.26,0.55,0.51,0.51,0.079,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10590000,0.71,0.0022,-0.013,0.71,0.006,-0.0082,0.024,0,0,-4.9e+02,-0.0016,-0.0059,-7.9e-05,-0.0024,0.0018,-0.098,0.21,-4.5e-06,0.43,-0.00029,0.00053,-0.00017,0,0,-4.9e+02,0.0012,0.0011,0.039,0.13,0.13,0.27,0.17,0.17,0.072,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10690000,0.71,0.0021,-0.013,0.71,0.0033,-0.009,0.027,0,0,-4.9e+02,-0.0015,-0.0059,-8.1e-05,-0.0024,0.0018,-0.098,0.21,-4.1e-06,0.43,-0.00027,0.00052,-0.00017,0,0,-4.9e+02,0.0012,0.0011,0.039,0.14,0.14,0.26,0.18,0.18,0.077,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10790000,0.71,0.002,-0.013,0.71,0.0034,-0.0064,0.021,0,0,-4.9e+02,-0.0015,-0.0059,-8e-05,-0.0025,0.0021,-0.098,0.21,-4e-06,0.43,-0.00026,0.00056,-0.00016,0,0,-4.9e+02,0.0012,0.0011,0.038,0.093,0.094,0.17,0.11,0.11,0.071,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10890000,0.71,0.0019,-0.013,0.71,0.0021,-0.0066,0.016,0,0,-4.9e+02,-0.0015,-0.0058,-8.1e-05,-0.0025,0.0021,-0.098,0.21,-3.7e-06,0.43,-0.00025,0.00057,-0.00015,0,0,-4.9e+02,0.0011,0.0011,0.038,0.1,0.1,0.16,0.11,0.11,0.074,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +10990000,0.71,0.0017,-0.014,0.71,0.0068,-0.0015,0.011,0,0,-4.9e+02,-0.0013,-0.0057,-7.9e-05,-0.0025,0.0031,-0.098,0.21,-3.2e-06,0.43,-0.00022,0.00071,-0.00011,0,0,-4.9e+02,0.0011,0.001,0.038,0.079,0.08,0.12,0.079,0.079,0.071,1.7e-05,3.1e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11090000,0.71,0.0017,-0.014,0.71,0.0068,0.0018,0.014,0,0,-4.9e+02,-0.0014,-0.0056,-7.5e-05,-0.0023,0.0029,-0.098,0.21,-3.3e-06,0.43,-0.00023,0.00078,-6.8e-05,0,0,-4.9e+02,0.0011,0.00099,0.038,0.09,0.091,0.12,0.085,0.085,0.073,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11190000,0.71,0.0017,-0.014,0.71,0.01,0.0034,0.0027,0,0,-4.9e+02,-0.0013,-0.0056,-7.8e-05,-0.0023,0.004,-0.098,0.21,-3.4e-06,0.43,-0.00024,0.00079,-8.6e-05,0,0,-4.9e+02,0.00098,0.00092,0.038,0.074,0.075,0.091,0.066,0.066,0.068,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11290000,0.71,0.0016,-0.014,0.71,0.0094,0.0018,0.0014,0,0,-4.9e+02,-0.0013,-0.0057,-8.3e-05,-0.0026,0.0043,-0.098,0.21,-3e-06,0.43,-0.00022,0.00073,-0.00011,0,0,-4.9e+02,0.00098,0.00091,0.038,0.086,0.087,0.087,0.072,0.072,0.071,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11390000,0.71,0.0016,-0.013,0.71,0.0049,0.00087,-0.0044,0,0,-4.9e+02,-0.0013,-0.0058,-8.6e-05,-0.0033,0.0041,-0.098,0.21,-3e-06,0.43,-0.00021,0.00066,-0.00016,0,0,-4.9e+02,0.00087,0.00082,0.038,0.072,0.073,0.072,0.058,0.058,0.067,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11490000,0.71,0.0014,-0.013,0.71,0.0011,-0.002,-0.0044,0,0,-4.9e+02,-0.0012,-0.0059,-9.3e-05,-0.0039,0.0049,-0.098,0.21,-2.7e-06,0.43,-0.00018,0.00056,-0.00022,0,0,-4.9e+02,0.00086,0.00081,0.038,0.083,0.086,0.069,0.064,0.064,0.068,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11590000,0.71,0.0013,-0.013,0.71,-0.002,-0.0015,-0.01,0,0,-4.9e+02,-0.0012,-0.0059,-9.4e-05,-0.0045,0.005,-0.098,0.21,-2.5e-06,0.43,-0.00016,0.00054,-0.00023,0,0,-4.9e+02,0.00075,0.00072,0.038,0.07,0.072,0.059,0.054,0.054,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11690000,0.71,0.0011,-0.013,0.71,-0.0035,-0.0027,-0.016,0,0,-4.9e+02,-0.0011,-0.006,-9.8e-05,-0.0053,0.0052,-0.098,0.21,-2e-06,0.43,-0.0001,0.00053,-0.00026,0,0,-4.9e+02,0.00075,0.00071,0.038,0.082,0.084,0.057,0.06,0.06,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11790000,0.71,0.0011,-0.013,0.71,-0.0075,-0.00084,-0.018,0,0,-4.9e+02,-0.0011,-0.006,-9.9e-05,-0.0071,0.0053,-0.098,0.21,-2e-06,0.43,-8.6e-05,0.0005,-0.00027,0,0,-4.9e+02,0.00065,0.00063,0.038,0.068,0.07,0.051,0.051,0.051,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11890000,0.71,0.00095,-0.013,0.71,-0.0085,-0.0037,-0.02,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0078,0.0059,-0.098,0.21,-1.9e-06,0.43,-5.4e-05,0.00047,-0.00032,0,0,-4.9e+02,0.00065,0.00062,0.038,0.08,0.082,0.049,0.058,0.058,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11990000,0.71,0.0013,-0.013,0.71,-0.012,0.0012,-0.026,0,0,-4.9e+02,-0.0011,-0.006,-9.9e-05,-0.0074,0.0064,-0.097,0.21,-2.9e-06,0.43,-0.00013,0.00048,-0.00032,0,0,-4.9e+02,0.00056,0.00055,0.037,0.066,0.068,0.045,0.049,0.049,0.062,9.2e-06,1.6e-05,2.3e-06,0.026,0.028,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +12090000,0.71,0.0014,-0.013,0.71,-0.013,0.0044,-0.032,0,0,-4.9e+02,-0.0012,-0.0059,-9.5e-05,-0.0063,0.0056,-0.097,0.21,-3e-06,0.43,-0.00016,0.00053,-0.00028,0,0,-4.9e+02,0.00056,0.00055,0.037,0.077,0.079,0.045,0.056,0.057,0.062,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12190000,0.71,0.0012,-0.013,0.71,-0.0068,0.004,-0.026,0,0,-4.9e+02,-0.0011,-0.0059,-9.6e-05,-0.0062,0.006,-0.099,0.21,-2.3e-06,0.43,-0.00011,0.0006,-0.00026,0,0,-4.9e+02,0.00048,0.00048,0.037,0.064,0.066,0.041,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12290000,0.71,0.001,-0.013,0.71,-0.0081,0.0044,-0.026,0,0,-4.9e+02,-0.0011,-0.0059,-9.6e-05,-0.0067,0.0056,-0.099,0.21,-2e-06,0.43,-8.1e-05,0.0006,-0.00026,0,0,-4.9e+02,0.00048,0.00048,0.037,0.073,0.076,0.042,0.056,0.056,0.06,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12390000,0.71,0.001,-0.013,0.71,-0.0053,0.0032,-0.023,0,0,-4.9e+02,-0.0011,-0.0059,-9.9e-05,-0.0053,0.0073,-0.1,0.21,-2.5e-06,0.43,-0.00012,0.00061,-0.00025,0,0,-4.9e+02,0.00042,0.00043,0.037,0.061,0.063,0.039,0.048,0.048,0.058,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12490000,0.71,0.00093,-0.013,0.71,-0.007,0.0028,-0.027,0,0,-4.9e+02,-0.0011,-0.0059,-0.0001,-0.0058,0.0085,-0.1,0.21,-2.7e-06,0.43,-0.00015,0.00054,-0.00025,0,0,-4.9e+02,0.00042,0.00042,0.037,0.069,0.072,0.04,0.055,0.055,0.058,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12590000,0.71,0.0011,-0.013,0.71,-0.014,0.0037,-0.033,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0051,0.0078,-0.1,0.21,-3e-06,0.43,-0.00019,0.00051,-0.00024,0,0,-4.9e+02,0.00037,0.00038,0.037,0.058,0.059,0.038,0.047,0.048,0.057,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12690000,0.71,0.0014,-0.013,0.71,-0.017,0.0046,-0.037,0,0,-4.9e+02,-0.0012,-0.006,-0.0001,-0.0034,0.0091,-0.1,0.21,-3.9e-06,0.43,-0.00026,0.0005,-0.00025,0,0,-4.9e+02,0.00037,0.00038,0.037,0.065,0.067,0.039,0.055,0.055,0.057,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12790000,0.71,0.0012,-0.013,0.71,-0.02,0.0027,-0.041,0,0,-4.9e+02,-0.0012,-0.006,-0.0001,-0.0049,0.008,-0.1,0.21,-3.3e-06,0.43,-0.0002,0.00048,-0.00027,0,0,-4.9e+02,0.00033,0.00034,0.037,0.054,0.056,0.037,0.047,0.047,0.056,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12890000,0.71,0.0011,-0.013,0.71,-0.019,0.0014,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0063,0.0076,-0.1,0.21,-2.8e-06,0.43,-0.00017,0.00047,-0.00026,0,0,-4.9e+02,0.00033,0.00034,0.037,0.061,0.063,0.038,0.054,0.055,0.057,6e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +12990000,0.71,0.001,-0.013,0.71,-0.009,0.0019,-0.039,0,0,-4.9e+02,-0.0011,-0.0059,-9.9e-05,-0.0039,0.008,-0.1,0.21,-2.7e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-4.9e+02,0.0003,0.00031,0.037,0.051,0.053,0.037,0.047,0.047,0.055,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13090000,0.71,0.00094,-0.013,0.71,-0.0097,-0.00016,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.005,0.0096,-0.1,0.21,-3e-06,0.43,-0.00019,0.00052,-0.00023,0,0,-4.9e+02,0.0003,0.00031,0.037,0.057,0.059,0.038,0.054,0.054,0.056,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13190000,0.71,0.00094,-0.013,0.71,-0.0023,0.0008,-0.034,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0032,0.011,-0.11,0.21,-3.4e-06,0.43,-0.00023,0.00056,-0.00021,0,0,-4.9e+02,0.00027,0.00029,0.037,0.048,0.05,0.037,0.047,0.047,0.054,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13290000,0.71,0.00079,-0.013,0.71,-0.00082,0.0015,-0.029,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0047,0.0096,-0.11,0.21,-2.5e-06,0.43,-0.00017,0.00058,-0.0002,0,0,-4.9e+02,0.00027,0.00028,0.037,0.054,0.055,0.038,0.054,0.054,0.055,5.1e-06,8.9e-06,2.3e-06,0.015,0.019,0.0097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13390000,0.71,0.0007,-0.013,0.71,0.00021,0.0023,-0.024,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0042,0.0088,-0.11,0.21,-2.3e-06,0.43,-0.00016,0.00063,-0.00019,0,0,-4.9e+02,0.00025,0.00026,0.037,0.045,0.047,0.037,0.047,0.047,0.054,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13490000,0.71,0.0007,-0.013,0.71,0.00018,0.0024,-0.022,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0042,0.0081,-0.11,0.21,-1.9e-06,0.43,-0.00014,0.00063,-0.00017,0,0,-4.9e+02,0.00025,0.00026,0.037,0.05,0.052,0.038,0.054,0.054,0.055,4.7e-06,8.2e-06,2.3e-06,0.014,0.018,0.009,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13590000,0.71,0.00072,-0.013,0.71,-5.1e-05,0.0028,-0.024,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.004,0.0093,-0.11,0.21,-2.4e-06,0.43,-0.00017,0.00062,-0.00019,0,0,-4.9e+02,0.00023,0.00025,0.037,0.042,0.044,0.037,0.046,0.047,0.054,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13690000,0.71,0.0007,-0.013,0.71,0.00087,0.0053,-0.029,0,0,-4.9e+02,-0.001,-0.0059,-9.9e-05,-0.0035,0.0081,-0.11,0.21,-2e-06,0.43,-0.00016,0.00064,-0.00016,0,0,-4.9e+02,0.00023,0.00024,0.037,0.047,0.049,0.038,0.053,0.054,0.055,4.3e-06,7.7e-06,2.3e-06,0.013,0.017,0.0083,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13790000,0.71,0.00074,-0.013,0.71,0.00057,0.0021,-0.03,0,0,-4.9e+02,-0.0011,-0.0059,-9.9e-05,-0.002,0.0088,-0.11,0.21,-2.4e-06,0.43,-0.00019,0.00065,-0.00015,0,0,-4.9e+02,0.00022,0.00023,0.037,0.04,0.041,0.036,0.046,0.046,0.053,4.2e-06,7.3e-06,2.3e-06,0.013,0.016,0.0078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13890000,0.71,0.00059,-0.013,0.71,0.0024,0.0021,-0.035,0,0,-4.9e+02,-0.001,-0.0059,-9.8e-05,-0.0034,0.0077,-0.11,0.21,-1.7e-06,0.43,-0.00015,0.00065,-0.00015,0,0,-4.9e+02,0.00022,0.00023,0.037,0.044,0.046,0.037,0.053,0.053,0.055,4e-06,7.1e-06,2.3e-06,0.012,0.016,0.0076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13990000,0.71,0.00065,-0.013,0.71,0.0018,0.0005,-0.034,0,0,-4.9e+02,-0.001,-0.0059,-9.8e-05,-0.0021,0.0083,-0.11,0.21,-2e-06,0.43,-0.00018,0.00065,-0.00013,0,0,-4.9e+02,0.00021,0.00022,0.037,0.037,0.039,0.036,0.046,0.046,0.054,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0071,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +14090000,0.71,0.00072,-0.013,0.71,0.0014,0.0019,-0.035,0,0,-4.9e+02,-0.0011,-0.0059,-9.4e-05,-0.00064,0.0072,-0.11,0.21,-1.8e-06,0.43,-0.00018,0.00068,-9.7e-05,0,0,-4.9e+02,0.00021,0.00022,0.037,0.041,0.043,0.036,0.053,0.053,0.054,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14190000,0.71,0.00068,-0.013,0.71,0.0044,0.0018,-0.037,0,0,-4.9e+02,-0.0011,-0.0059,-9.3e-05,-0.00018,0.007,-0.11,0.21,-1.6e-06,0.43,-0.00017,0.0007,-8e-05,0,0,-4.9e+02,0.0002,0.00021,0.037,0.035,0.037,0.035,0.046,0.046,0.054,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14290000,0.71,0.00075,-0.013,0.71,0.0046,0.0032,-0.035,0,0,-4.9e+02,-0.0011,-0.0058,-9.2e-05,0.00066,0.0069,-0.11,0.21,-1.7e-06,0.43,-0.00019,0.00071,-6.2e-05,0,0,-4.9e+02,0.0002,0.00021,0.037,0.039,0.04,0.036,0.052,0.052,0.055,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14390000,0.71,0.00063,-0.014,0.71,0.007,0.0049,-0.037,0,0,-4.9e+02,-0.0011,-0.0058,-8.9e-05,0.00034,0.0054,-0.11,0.21,-9e-07,0.43,-0.00015,0.00074,-4.6e-05,0,0,-4.9e+02,0.00019,0.0002,0.037,0.033,0.035,0.034,0.046,0.046,0.053,3.4e-06,6e-06,2.3e-06,0.011,0.014,0.0059,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14490000,0.71,0.00052,-0.013,0.71,0.008,0.0064,-0.041,0,0,-4.9e+02,-0.001,-0.0058,-8.9e-05,-0.00096,0.0049,-0.11,0.21,-4.1e-07,0.43,-0.00013,0.0007,-4.6e-05,0,0,-4.9e+02,0.00019,0.0002,0.037,0.036,0.038,0.035,0.052,0.052,0.054,3.3e-06,5.8e-06,2.3e-06,0.011,0.014,0.0057,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14590000,0.71,0.00042,-0.013,0.71,0.006,0.0049,-0.041,0,0,-4.9e+02,-0.001,-0.0058,-8.9e-05,-0.0019,0.0047,-0.11,0.21,-3.2e-07,0.43,-0.00012,0.00067,-5.9e-05,0,0,-4.9e+02,0.00018,0.00019,0.037,0.031,0.033,0.033,0.045,0.045,0.054,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0053,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14690000,0.71,0.00037,-0.013,0.71,0.0078,0.003,-0.038,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.0018,0.0038,-0.11,0.21,6.3e-08,0.43,-0.0001,0.00068,-4.6e-05,0,0,-4.9e+02,0.00018,0.00019,0.037,0.034,0.036,0.034,0.051,0.052,0.054,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14790000,0.71,0.00035,-0.013,0.71,0.0055,0.0016,-0.033,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.002,0.0036,-0.12,0.21,7.8e-09,0.43,-0.0001,0.00066,-4.7e-05,0,0,-4.9e+02,0.00017,0.00018,0.037,0.03,0.031,0.032,0.045,0.045,0.053,3e-06,5.2e-06,2.3e-06,0.0098,0.013,0.0048,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14890000,0.71,0.00032,-0.013,0.71,0.0077,0.0033,-0.037,0,0,-4.9e+02,-0.001,-0.0058,-8.6e-05,-0.0022,0.0031,-0.12,0.21,2.7e-07,0.43,-9e-05,0.00067,-4.4e-05,0,0,-4.9e+02,0.00017,0.00018,0.037,0.032,0.034,0.032,0.051,0.051,0.055,2.9e-06,5.1e-06,2.3e-06,0.0097,0.013,0.0046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +14990000,0.71,0.00027,-0.013,0.71,0.0067,0.0023,-0.032,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.0028,0.0036,-0.12,0.21,7.5e-08,0.43,-9.9e-05,0.00064,-5.6e-05,0,0,-4.9e+02,0.00017,0.00017,0.037,0.028,0.03,0.031,0.045,0.045,0.053,2.8e-06,4.9e-06,2.3e-06,0.0094,0.013,0.0043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15090000,0.71,0.0002,-0.013,0.71,0.0075,0.0024,-0.035,0,0,-4.9e+02,-0.001,-0.0058,-8.8e-05,-0.0029,0.004,-0.12,0.21,-2.8e-08,0.43,-0.00011,0.00063,-5.7e-05,0,0,-4.9e+02,0.00017,0.00017,0.037,0.031,0.032,0.031,0.05,0.051,0.054,2.7e-06,4.8e-06,2.3e-06,0.0093,0.012,0.0041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15190000,0.71,0.00016,-0.013,0.7,0.0072,0.003,-0.033,0,0,-4.9e+02,-0.001,-0.0058,-9e-05,-0.0035,0.0043,-0.12,0.21,-2.3e-08,0.43,-0.00012,0.00059,-6.4e-05,0,0,-4.9e+02,0.00016,0.00017,0.037,0.027,0.028,0.03,0.044,0.045,0.053,2.6e-06,4.6e-06,2.3e-06,0.0091,0.012,0.0038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15290000,0.71,0.00019,-0.013,0.7,0.0077,0.0041,-0.03,0,0,-4.9e+02,-0.001,-0.0058,-8.8e-05,-0.0026,0.0041,-0.12,0.21,2.1e-08,0.43,-0.00014,0.00059,-4e-05,0,0,-4.9e+02,0.00016,0.00017,0.037,0.029,0.031,0.03,0.05,0.05,0.054,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15390000,0.71,0.0002,-0.013,0.7,0.007,0.0053,-0.028,0,0,-4.9e+02,-0.001,-0.0058,-8.3e-05,-0.0018,0.0027,-0.12,0.21,3.7e-07,0.43,-0.00012,0.00062,-1.7e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.025,0.027,0.028,0.044,0.044,0.053,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15490000,0.71,0.00021,-0.013,0.7,0.0085,0.0045,-0.028,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.0022,0.004,-0.12,0.21,-8e-08,0.43,-0.00014,0.00059,-3.5e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.027,0.029,0.029,0.049,0.05,0.054,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15590000,0.71,0.00018,-0.013,0.71,0.0071,0.0035,-0.027,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.0028,0.0047,-0.12,0.21,-4.3e-07,0.43,-0.00014,0.00058,-6.1e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.024,0.026,0.027,0.044,0.044,0.053,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15690000,0.71,0.00022,-0.013,0.71,0.0074,0.0036,-0.028,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.0023,0.0051,-0.12,0.21,-7.3e-07,0.43,-0.00015,0.00058,-6.4e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.026,0.028,0.027,0.049,0.049,0.053,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15790000,0.71,0.00019,-0.013,0.7,0.008,0.002,-0.03,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.0026,0.0053,-0.12,0.21,-8.4e-07,0.43,-0.00016,0.00057,-6.8e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.023,0.025,0.026,0.043,0.044,0.052,2.2e-06,3.9e-06,2.3e-06,0.0082,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15890000,0.71,0.0002,-0.013,0.71,0.0087,0.0021,-0.028,0,0,-4.9e+02,-0.0011,-0.0059,-8.8e-05,-0.0018,0.0056,-0.12,0.21,-1e-06,0.43,-0.00018,0.00057,-6e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.025,0.027,0.026,0.048,0.049,0.053,2.1e-06,3.8e-06,2.3e-06,0.0081,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15990000,0.71,0.00017,-0.013,0.71,0.0085,0.0022,-0.024,0,0,-4.9e+02,-0.0011,-0.0059,-8.4e-05,-0.0012,0.0049,-0.12,0.21,-9.4e-07,0.43,-0.00018,0.00058,-4.2e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.022,0.024,0.025,0.043,0.043,0.052,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +16090000,0.71,0.00021,-0.013,0.71,0.01,0.0038,-0.02,0,0,-4.9e+02,-0.0011,-0.0058,-8e-05,-0.00044,0.0036,-0.12,0.21,-6.7e-07,0.43,-0.00016,0.00063,-2.6e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.024,0.026,0.024,0.048,0.049,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16190000,0.71,0.00026,-0.013,0.71,0.01,0.004,-0.019,0,0,-4.9e+02,-0.0011,-0.0058,-7.9e-05,0.0003,0.0038,-0.12,0.21,-9.9e-07,0.43,-0.00017,0.00063,-2.1e-05,0,0,-4.9e+02,0.00015,0.00014,0.037,0.021,0.023,0.023,0.043,0.043,0.052,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16290000,0.71,0.00028,-0.014,0.71,0.012,0.0051,-0.02,0,0,-4.9e+02,-0.0011,-0.0058,-7.5e-05,0.00062,0.0025,-0.12,0.21,-5.3e-07,0.43,-0.00015,0.00064,-5.9e-06,0,0,-4.9e+02,0.00015,0.00014,0.037,0.023,0.025,0.023,0.048,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16390000,0.71,0.00033,-0.013,0.71,0.01,0.0036,-0.019,0,0,-4.9e+02,-0.0011,-0.0058,-7.6e-05,0.0017,0.0037,-0.12,0.21,-1.3e-06,0.43,-0.00018,0.00064,-2e-06,0,0,-4.9e+02,0.00014,0.00014,0.037,0.02,0.023,0.022,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0075,0.0098,0.002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16490000,0.71,0.00042,-0.013,0.71,0.0087,0.0049,-0.022,0,0,-4.9e+02,-0.0011,-0.0058,-7.5e-05,0.0026,0.0039,-0.12,0.21,-1.5e-06,0.43,-0.00019,0.00064,1.2e-05,0,0,-4.9e+02,0.00014,0.00014,0.037,0.022,0.024,0.022,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0019,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16590000,0.71,0.00052,-0.013,0.71,0.0066,0.0058,-0.023,0,0,-4.9e+02,-0.0012,-0.0058,-7.6e-05,0.0027,0.0036,-0.12,0.21,-1.6e-06,0.43,-0.00017,0.00063,7.8e-06,0,0,-4.9e+02,0.00014,0.00014,0.037,0.02,0.022,0.021,0.042,0.042,0.05,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0096,0.0018,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16690000,0.71,0.00049,-0.013,0.71,0.0075,0.0062,-0.019,0,0,-4.9e+02,-0.0012,-0.0058,-7.9e-05,0.0022,0.0042,-0.12,0.21,-1.7e-06,0.43,-0.00018,0.00062,-3.3e-06,0,0,-4.9e+02,0.00014,0.00014,0.037,0.021,0.024,0.021,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0017,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16790000,0.71,0.00048,-0.013,0.71,0.0056,0.0068,-0.018,0,0,-4.9e+02,-0.0012,-0.0058,-8e-05,0.002,0.0039,-0.12,0.21,-1.7e-06,0.43,-0.00016,0.00063,-1.6e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.019,0.021,0.02,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0093,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16890000,0.71,0.00054,-0.013,0.71,0.0053,0.0078,-0.016,0,0,-4.9e+02,-0.0012,-0.0058,-8.2e-05,0.0023,0.0045,-0.13,0.21,-2e-06,0.43,-0.00017,0.00062,-1.2e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.02,0.023,0.02,0.046,0.047,0.05,1.6e-06,2.8e-06,2.3e-06,0.007,0.0092,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +16990000,0.71,0.00051,-0.013,0.71,0.0054,0.0055,-0.015,0,0,-4.9e+02,-0.0012,-0.0059,-8.2e-05,0.0022,0.0056,-0.13,0.21,-2.4e-06,0.43,-0.00019,0.00061,-2.2e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.018,0.021,0.019,0.041,0.042,0.049,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17090000,0.71,0.00055,-0.013,0.71,0.0057,0.007,-0.015,0,0,-4.9e+02,-0.0012,-0.0059,-8.1e-05,0.0032,0.0059,-0.13,0.21,-2.7e-06,0.43,-0.0002,0.00061,-1e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.02,0.022,0.019,0.046,0.047,0.049,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17190000,0.71,0.00061,-0.013,0.71,0.0058,0.0079,-0.016,0,0,-4.9e+02,-0.0012,-0.0059,-7.7e-05,0.0039,0.0058,-0.13,0.21,-3e-06,0.43,-0.0002,0.00062,-7.8e-06,0,0,-4.9e+02,0.00013,0.00013,0.037,0.018,0.02,0.018,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0068,0.0088,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17290000,0.71,0.00063,-0.013,0.71,0.0076,0.0087,-0.011,0,0,-4.9e+02,-0.0012,-0.0059,-7.9e-05,0.0043,0.0068,-0.13,0.21,-3.4e-06,0.43,-0.00022,0.00061,-5.2e-06,0,0,-4.9e+02,0.00013,0.00013,0.037,0.019,0.022,0.018,0.045,0.046,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0087,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17390000,0.71,0.00068,-0.013,0.71,0.0074,0.0091,-0.0095,0,0,-4.9e+02,-0.0012,-0.0059,-7.3e-05,0.0051,0.0065,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.017,0.02,0.017,0.041,0.041,0.048,1.4e-06,2.5e-06,2.2e-06,0.0066,0.0085,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17490000,0.71,0.00063,-0.013,0.71,0.009,0.0093,-0.0078,0,0,-4.9e+02,-0.0012,-0.0059,-7.4e-05,0.0045,0.0063,-0.13,0.21,-3.3e-06,0.43,-0.00023,0.00061,7.8e-06,0,0,-4.9e+02,0.00013,0.00012,0.037,0.019,0.021,0.017,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17590000,0.71,0.0006,-0.013,0.71,0.0098,0.0084,-0.0024,0,0,-4.9e+02,-0.0012,-0.0059,-7e-05,0.0048,0.0065,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,5.1e-06,0,0,-4.9e+02,0.00013,0.00012,0.037,0.017,0.019,0.017,0.04,0.041,0.048,1.4e-06,2.3e-06,2.2e-06,0.0065,0.0083,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17690000,0.71,0.00057,-0.013,0.71,0.011,0.01,-0.003,0,0,-4.9e+02,-0.0012,-0.0059,-6.9e-05,0.0049,0.0063,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.045,0.046,0.048,1.3e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17790000,0.71,0.00056,-0.013,0.71,0.012,0.011,-0.0042,0,0,-4.9e+02,-0.0012,-0.0058,-6e-05,0.0059,0.0052,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00064,2.3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.0081,0.001,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17890000,0.71,0.00055,-0.013,0.71,0.015,0.012,-0.0041,0,0,-4.9e+02,-0.0012,-0.0058,-5.8e-05,0.0057,0.0046,-0.13,0.21,-3.2e-06,0.43,-0.00023,0.00064,2.8e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.044,0.045,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.00097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17990000,0.71,0.00049,-0.013,0.71,0.016,0.009,-0.0027,0,0,-4.9e+02,-0.0012,-0.0058,-5.7e-05,0.0054,0.0049,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00064,2.5e-05,0,0,-4.9e+02,0.00012,0.00012,0.037,0.016,0.019,0.015,0.04,0.041,0.046,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0079,0.00092,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +18090000,0.71,0.00047,-0.013,0.71,0.017,0.0082,-0.00045,0,0,-4.9e+02,-0.0012,-0.0059,-6.2e-05,0.0049,0.0058,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00061,1.9e-05,0,0,-4.9e+02,0.00012,0.00012,0.037,0.017,0.02,0.015,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00089,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18190000,0.71,0.00043,-0.013,0.71,0.017,0.0092,0.001,0,0,-4.9e+02,-0.0012,-0.0059,-5.8e-05,0.0051,0.0055,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00062,2e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.018,0.014,0.04,0.041,0.046,1.2e-06,2e-06,2.2e-06,0.0061,0.0077,0.00085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18290000,0.71,0.00035,-0.013,0.71,0.018,0.0088,0.0022,0,0,-4.9e+02,-0.0012,-0.0059,-6e-05,0.0047,0.0058,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00061,1.4e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.017,0.02,0.014,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00082,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18390000,0.71,0.00031,-0.013,0.71,0.02,0.011,0.0035,0,0,-4.9e+02,-0.0012,-0.0059,-5.4e-05,0.0044,0.005,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00062,1.6e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.045,1.1e-06,1.9e-06,2.2e-06,0.006,0.0075,0.00078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18490000,0.71,0.00038,-0.013,0.71,0.021,0.012,0.0031,0,0,-4.9e+02,-0.0012,-0.0059,-5.3e-05,0.005,0.0051,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00063,2e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.02,0.014,0.043,0.045,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18590000,0.71,0.00039,-0.013,0.71,0.02,0.013,0.0014,0,0,-4.9e+02,-0.0012,-0.0058,-4.5e-05,0.0058,0.0046,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00065,2.5e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0073,0.00072,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18690000,0.71,0.00031,-0.013,0.71,0.022,0.012,-0.00039,0,0,-4.9e+02,-0.0012,-0.0059,-4.7e-05,0.0051,0.0046,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00064,1.9e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1e-06,1.8e-06,2.2e-06,0.0058,0.0072,0.0007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18790000,0.71,0.00032,-0.013,0.71,0.021,0.012,-0.00061,0,0,-4.9e+02,-0.0012,-0.0059,-4.6e-05,0.0053,0.0052,-0.13,0.21,-3.8e-06,0.43,-0.00025,0.00063,1.6e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00067,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18890000,0.71,0.00041,-0.013,0.71,0.021,0.014,1.9e-05,0,0,-4.9e+02,-0.0012,-0.0058,-4e-05,0.0062,0.0046,-0.13,0.21,-3.8e-06,0.43,-0.00026,0.00065,2.9e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +18990000,0.71,0.00046,-0.013,0.71,0.021,0.015,-0.0012,0,0,-4.9e+02,-0.0013,-0.0058,-3.4e-05,0.0069,0.0048,-0.13,0.21,-4.1e-06,0.43,-0.00027,0.00066,3e-05,0,0,-4.9e+02,0.00011,0.0001,0.037,0.015,0.017,0.012,0.039,0.04,0.044,9.7e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00062,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19090000,0.71,0.00051,-0.013,0.71,0.021,0.016,0.0018,0,0,-4.9e+02,-0.0013,-0.0058,-3.4e-05,0.0075,0.0051,-0.13,0.21,-4.4e-06,0.43,-0.00028,0.00066,3.4e-05,0,0,-4.9e+02,0.00011,0.0001,0.037,0.016,0.019,0.012,0.042,0.044,0.044,9.6e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.0006,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19190000,0.71,0.00055,-0.013,0.71,0.02,0.016,0.0019,0,0,-4.9e+02,-0.0013,-0.0059,-2.7e-05,0.008,0.0053,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00067,3.8e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.043,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.00058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19290000,0.71,0.00058,-0.013,0.71,0.02,0.015,0.0046,0,0,-4.9e+02,-0.0013,-0.0059,-3.1e-05,0.0078,0.0057,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00066,4e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.015,0.019,0.012,0.042,0.044,0.043,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19390000,0.71,0.00054,-0.013,0.71,0.019,0.014,0.0084,0,0,-4.9e+02,-0.0013,-0.0059,-2.4e-05,0.0078,0.0055,-0.13,0.21,-4.7e-06,0.43,-0.00029,0.00065,3.6e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.014,0.017,0.011,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0055,0.0066,0.00054,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19490000,0.71,0.00055,-0.013,0.71,0.019,0.015,0.0049,0,0,-4.9e+02,-0.0013,-0.0058,-1.9e-05,0.0078,0.0048,-0.13,0.21,-4.5e-06,0.43,-0.00029,0.00066,3.9e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.015,0.018,0.011,0.042,0.044,0.043,8.8e-07,1.4e-06,2.1e-06,0.0054,0.0066,0.00052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19590000,0.71,0.00063,-0.013,0.71,0.017,0.015,0.0043,0,0,-4.9e+02,-0.0013,-0.0058,-7.4e-06,0.0086,0.0046,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00068,4.7e-05,0,0,-4.9e+02,0.00011,9.8e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.5e-07,1.4e-06,2.1e-06,0.0054,0.0065,0.0005,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19690000,0.71,0.00067,-0.013,0.71,0.017,0.013,0.0059,0,0,-4.9e+02,-0.0013,-0.0058,-1.1e-05,0.0089,0.0052,-0.13,0.21,-4.9e-06,0.43,-0.0003,0.00068,3.9e-05,0,0,-4.9e+02,0.00011,9.8e-05,0.036,0.015,0.018,0.011,0.042,0.043,0.042,8.4e-07,1.4e-06,2.1e-06,0.0053,0.0065,0.00049,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19790000,0.71,0.00074,-0.013,0.71,0.014,0.011,0.0064,0,0,-4.9e+02,-0.0013,-0.0059,-6.3e-06,0.0094,0.0055,-0.13,0.21,-5.2e-06,0.43,-0.00031,0.00068,3.8e-05,0,0,-4.9e+02,0.00011,9.6e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0064,0.00047,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19890000,0.71,0.00066,-0.013,0.71,0.015,0.013,0.0076,0,0,-4.9e+02,-0.0013,-0.0058,1.8e-06,0.0092,0.0045,-0.13,0.21,-4.9e-06,0.43,-0.0003,0.00069,4.5e-05,0,0,-4.9e+02,0.00011,9.6e-05,0.036,0.015,0.018,0.01,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19990000,0.71,0.00063,-0.013,0.7,0.013,0.013,0.01,0,0,-4.9e+02,-0.0013,-0.0058,1.7e-05,0.0095,0.0037,-0.13,0.21,-4.8e-06,0.43,-0.0003,0.0007,5.1e-05,0,0,-4.9e+02,0.0001,9.4e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.041,7.9e-07,1.3e-06,2.1e-06,0.0052,0.0062,0.00044,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +20090000,0.71,0.00066,-0.013,0.7,0.013,0.013,0.011,0,0,-4.9e+02,-0.0013,-0.0058,2.7e-05,0.01,0.0029,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00072,6.2e-05,0,0,-4.9e+02,0.00011,9.5e-05,0.036,0.014,0.018,0.01,0.041,0.043,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20190000,0.71,0.00069,-0.013,0.7,0.012,0.012,0.013,0,0,-4.9e+02,-0.0013,-0.0058,3.6e-05,0.0099,0.0026,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00072,6.1e-05,0,0,-4.9e+02,0.0001,9.3e-05,0.036,0.013,0.016,0.0098,0.038,0.039,0.041,7.6e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00042,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20290000,0.71,0.0007,-0.013,0.7,0.01,0.012,0.011,0,0,-4.9e+02,-0.0013,-0.0058,4e-05,0.01,0.0025,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00073,6.3e-05,0,0,-4.9e+02,0.0001,9.3e-05,0.036,0.014,0.018,0.0097,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.0004,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20390000,0.71,0.00065,-0.013,0.7,0.0085,0.0097,0.013,0,0,-4.9e+02,-0.0013,-0.0058,4.4e-05,0.01,0.0026,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00073,5.3e-05,0,0,-4.9e+02,0.0001,9.1e-05,0.036,0.013,0.016,0.0095,0.037,0.039,0.04,7.3e-07,1.1e-06,2e-06,0.0051,0.006,0.00039,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20490000,0.71,0.00071,-0.013,0.7,0.0086,0.0096,0.013,0,0,-4.9e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0029,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00072,5.1e-05,0,0,-4.9e+02,0.0001,9.1e-05,0.036,0.014,0.017,0.0094,0.041,0.043,0.04,7.2e-07,1.1e-06,2e-06,0.005,0.006,0.00038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20590000,0.71,0.00074,-0.013,0.7,0.0077,0.0076,0.0099,0,0,-4.9e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0035,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00072,5.1e-05,0,0,-4.9e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0092,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0059,0.00037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20690000,0.71,0.00077,-0.013,0.7,0.0084,0.0076,0.011,0,0,-4.9e+02,-0.0013,-0.0058,4.5e-05,0.01,0.0032,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00072,5.2e-05,0,0,-4.9e+02,0.0001,8.9e-05,0.036,0.014,0.017,0.0092,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.005,0.0058,0.00036,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20790000,0.71,0.0008,-0.013,0.7,0.0062,0.0071,0.012,0,0,-4.9e+02,-0.0013,-0.0058,5e-05,0.011,0.0034,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00073,4.7e-05,0,0,-4.9e+02,9.8e-05,8.8e-05,0.036,0.013,0.016,0.009,0.037,0.039,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0058,0.00035,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20890000,0.71,0.00081,-0.013,0.7,0.0061,0.0068,0.011,0,0,-4.9e+02,-0.0013,-0.0058,5.8e-05,0.011,0.003,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00074,5.2e-05,0,0,-4.9e+02,9.9e-05,8.8e-05,0.036,0.014,0.017,0.0089,0.04,0.043,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +20990000,0.71,0.00083,-0.013,0.7,0.0044,0.0045,0.011,0,0,-4.9e+02,-0.0013,-0.0058,6.2e-05,0.011,0.0032,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00074,4.9e-05,0,0,-4.9e+02,9.6e-05,8.6e-05,0.036,0.013,0.016,0.0087,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0049,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21090000,0.71,0.00081,-0.013,0.7,0.0053,0.0037,0.012,0,0,-4.9e+02,-0.0013,-0.0058,6.7e-05,0.011,0.0027,-0.13,0.21,-4.8e-06,0.43,-0.00033,0.00075,4.6e-05,0,0,-4.9e+02,9.7e-05,8.6e-05,0.036,0.014,0.017,0.0087,0.04,0.043,0.039,6.4e-07,9.9e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21190000,0.71,0.00081,-0.013,0.7,0.0056,0.0028,0.011,0,0,-4.9e+02,-0.0013,-0.0058,6.7e-05,0.011,0.0029,-0.13,0.21,-4.7e-06,0.43,-0.00032,0.00075,4.3e-05,0,0,-4.9e+02,9.5e-05,8.5e-05,0.036,0.013,0.016,0.0085,0.037,0.039,0.039,6.3e-07,9.5e-07,2e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21290000,0.71,0.0009,-0.013,0.7,0.0049,0.0029,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.8e-05,0.011,0.0025,-0.13,0.21,-4.7e-06,0.43,-0.00033,0.00077,4.7e-05,0,0,-4.9e+02,9.5e-05,8.5e-05,0.036,0.014,0.017,0.0084,0.04,0.043,0.038,6.2e-07,9.5e-07,1.9e-06,0.0048,0.0055,0.00031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21390000,0.71,0.00088,-0.013,0.7,0.0039,0.00086,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.3e-05,0.011,0.0026,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00076,4.8e-05,0,0,-4.9e+02,9.3e-05,8.3e-05,0.036,0.013,0.016,0.0083,0.037,0.039,0.038,6e-07,9.1e-07,1.9e-06,0.0047,0.0055,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21490000,0.71,0.00088,-0.013,0.7,0.0044,0.0013,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.7e-05,0.011,0.0023,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00076,5.3e-05,0,0,-4.9e+02,9.4e-05,8.4e-05,0.036,0.014,0.017,0.0082,0.04,0.043,0.038,6e-07,9.1e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21590000,0.71,0.00087,-0.013,0.7,0.0033,0.0018,0.012,0,0,-4.9e+02,-0.0013,-0.0058,7.6e-05,0.011,0.0023,-0.13,0.21,-5e-06,0.43,-0.00032,0.00076,5e-05,0,0,-4.9e+02,9.2e-05,8.2e-05,0.036,0.013,0.015,0.0081,0.037,0.039,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0054,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21690000,0.71,0.00084,-0.013,0.7,0.0049,0.0021,0.014,0,0,-4.9e+02,-0.0013,-0.0058,8e-05,0.011,0.0019,-0.13,0.21,-4.9e-06,0.43,-0.0003,0.00076,5.1e-05,0,0,-4.9e+02,9.2e-05,8.2e-05,0.036,0.013,0.017,0.0081,0.04,0.042,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0053,0.00028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21790000,0.71,0.00083,-0.013,0.7,0.003,0.0042,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.1e-05,0.011,0.0021,-0.13,0.21,-5.5e-06,0.43,-0.00032,0.00076,5.3e-05,0,0,-4.9e+02,9e-05,8.1e-05,0.036,0.012,0.015,0.0079,0.037,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0053,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21890000,0.71,0.00083,-0.013,0.7,0.0038,0.0048,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.1e-05,0.011,0.002,-0.13,0.21,-5.4e-06,0.43,-0.00032,0.00076,5.1e-05,0,0,-4.9e+02,9.1e-05,8.1e-05,0.036,0.013,0.016,0.0079,0.04,0.042,0.037,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0053,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21990000,0.71,0.00085,-0.013,0.7,0.0025,0.0054,0.014,0,0,-4.9e+02,-0.0013,-0.0058,6.9e-05,0.012,0.0019,-0.13,0.21,-5.8e-06,0.43,-0.00033,0.00076,5.2e-05,0,0,-4.9e+02,8.9e-05,7.9e-05,0.036,0.012,0.015,0.0077,0.036,0.038,0.037,5.5e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22090000,0.71,0.00087,-0.013,0.7,0.0024,0.007,0.012,0,0,-4.9e+02,-0.0013,-0.0058,6.9e-05,0.012,0.0019,-0.13,0.21,-5.8e-06,0.43,-0.00033,0.00076,5.2e-05,0,0,-4.9e+02,8.9e-05,8e-05,0.036,0.013,0.016,0.0077,0.04,0.042,0.037,5.4e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22190000,0.71,0.00084,-0.013,0.7,0.0019,0.007,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.5e-05,0.012,0.002,-0.13,0.21,-5.6e-06,0.43,-0.00034,0.00077,4.2e-05,0,0,-4.9e+02,8.7e-05,7.8e-05,0.036,0.012,0.015,0.0076,0.036,0.038,0.037,5.3e-07,7.7e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22290000,0.71,0.00087,-0.013,0.7,0.0013,0.0067,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.2e-05,0.012,0.002,-0.13,0.21,-5.6e-06,0.43,-0.00034,0.00076,4.3e-05,0,0,-4.9e+02,8.8e-05,7.8e-05,0.036,0.013,0.016,0.0075,0.04,0.042,0.037,5.2e-07,7.7e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22390000,0.71,0.00089,-0.013,0.7,-0.0011,0.0064,0.015,0,0,-4.9e+02,-0.0013,-0.0058,7.9e-05,0.012,0.0023,-0.13,0.21,-5.6e-06,0.43,-0.00034,0.00077,4.4e-05,0,0,-4.9e+02,8.6e-05,7.7e-05,0.036,0.012,0.015,0.0074,0.036,0.038,0.037,5.1e-07,7.4e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22490000,0.71,0.00093,-0.013,0.7,-0.0022,0.0073,0.016,0,0,-4.9e+02,-0.0013,-0.0058,8e-05,0.012,0.0024,-0.13,0.21,-5.5e-06,0.43,-0.00036,0.00078,4.1e-05,0,0,-4.9e+02,8.7e-05,7.7e-05,0.036,0.013,0.016,0.0074,0.039,0.042,0.037,5.1e-07,7.4e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22590000,0.71,0.00095,-0.013,0.7,-0.0038,0.0066,0.015,0,0,-4.9e+02,-0.0014,-0.0058,8.4e-05,0.013,0.0026,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00079,3.8e-05,0,0,-4.9e+02,8.5e-05,7.6e-05,0.036,0.012,0.015,0.0073,0.036,0.038,0.036,5e-07,7.1e-07,1.8e-06,0.0044,0.005,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22690000,0.71,0.001,-0.013,0.7,-0.0052,0.008,0.016,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.013,0.0025,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.0008,3.8e-05,0,0,-4.9e+02,8.5e-05,7.6e-05,0.036,0.013,0.016,0.0073,0.039,0.042,0.036,4.9e-07,7.1e-07,1.8e-06,0.0044,0.005,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22790000,0.71,0.001,-0.013,0.7,-0.0072,0.0069,0.017,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.013,0.0033,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00078,4.3e-05,0,0,-4.9e+02,8.3e-05,7.5e-05,0.036,0.012,0.015,0.0071,0.036,0.038,0.036,4.8e-07,6.8e-07,1.8e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22890000,0.71,0.00099,-0.013,0.7,-0.0076,0.0078,0.019,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.013,0.0031,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00077,3.9e-05,0,0,-4.9e+02,8.4e-05,7.5e-05,0.036,0.013,0.016,0.0071,0.039,0.042,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22990000,0.71,0.00097,-0.013,0.7,-0.0077,0.0069,0.02,0,0,-4.9e+02,-0.0014,-0.0058,8.8e-05,0.013,0.003,-0.13,0.21,-5.2e-06,0.43,-0.00037,0.00078,3.6e-05,0,0,-4.9e+02,8.2e-05,7.4e-05,0.036,0.012,0.015,0.007,0.036,0.038,0.036,4.7e-07,6.6e-07,1.7e-06,0.0044,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23090000,0.71,0.00092,-0.013,0.7,-0.0081,0.0068,0.02,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.012,0.0033,-0.13,0.21,-5.4e-06,0.43,-0.00037,0.00076,3.4e-05,0,0,-4.9e+02,8.3e-05,7.4e-05,0.036,0.013,0.016,0.007,0.039,0.042,0.036,4.7e-07,6.6e-07,1.7e-06,0.0044,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23190000,0.71,0.00097,-0.013,0.7,-0.0094,0.0048,0.022,0,0,-4.9e+02,-0.0014,-0.0058,8.2e-05,0.013,0.0035,-0.13,0.21,-5.4e-06,0.43,-0.00036,0.00076,2.6e-05,0,0,-4.9e+02,8.1e-05,7.3e-05,0.036,0.012,0.014,0.0069,0.036,0.038,0.035,4.6e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23290000,0.71,0.00089,-0.013,0.7,-0.0093,0.0042,0.022,0,0,-4.9e+02,-0.0014,-0.0058,8.4e-05,0.012,0.0033,-0.13,0.21,-5.3e-06,0.43,-0.00036,0.00076,2.5e-05,0,0,-4.9e+02,8.2e-05,7.3e-05,0.036,0.013,0.016,0.0069,0.039,0.042,0.036,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23390000,0.71,0.00095,-0.013,0.7,-0.0095,0.003,0.02,0,0,-4.9e+02,-0.0014,-0.0058,8.7e-05,0.012,0.0033,-0.13,0.21,-5.4e-06,0.43,-0.00034,0.00075,2.6e-05,0,0,-4.9e+02,8e-05,7.2e-05,0.036,0.012,0.014,0.0068,0.036,0.038,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23490000,0.71,0.0033,-0.01,0.7,-0.016,0.0033,-0.013,0,0,-4.9e+02,-0.0014,-0.0058,9.3e-05,0.012,0.0031,-0.13,0.21,-5.4e-06,0.43,-0.00033,0.00078,5.1e-05,0,0,-4.9e+02,8.1e-05,7.2e-05,0.036,0.013,0.015,0.0068,0.039,0.042,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 +23590000,0.71,0.0086,-0.0026,0.7,-0.027,0.0032,-0.045,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.012,0.0031,-0.13,0.21,-5.3e-06,0.43,-0.00033,0.00084,0.00012,0,0,-4.9e+02,7.9e-05,7.1e-05,0.036,0.012,0.014,0.0067,0.036,0.038,0.035,4.3e-07,5.9e-07,1.6e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23690000,0.71,0.0082,0.0032,0.71,-0.058,-0.0046,-0.095,0,0,-4.9e+02,-0.0014,-0.0058,9e-05,0.012,0.0031,-0.13,0.21,-5.3e-06,0.43,-0.00033,0.00078,9e-05,0,0,-4.9e+02,8e-05,7.1e-05,0.036,0.013,0.015,0.0067,0.039,0.042,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0047,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23790000,0.71,0.0052,-0.00012,0.71,-0.083,-0.016,-0.15,0,0,-4.9e+02,-0.0013,-0.0058,9.1e-05,0.011,0.0026,-0.13,0.21,-4.5e-06,0.43,-0.00038,0.00078,0.00044,0,0,-4.9e+02,7.8e-05,7e-05,0.036,0.012,0.014,0.0066,0.036,0.038,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23890000,0.71,0.0026,-0.0062,0.71,-0.1,-0.025,-0.2,0,0,-4.9e+02,-0.0013,-0.0058,9.1e-05,0.012,0.0028,-0.13,0.21,-4.4e-06,0.43,-0.00041,0.00083,0.00035,0,0,-4.9e+02,7.9e-05,7e-05,0.036,0.013,0.016,0.0066,0.039,0.042,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23990000,0.71,0.0012,-0.011,0.71,-0.1,-0.029,-0.26,0,0,-4.9e+02,-0.0013,-0.0058,9.6e-05,0.012,0.0028,-0.13,0.21,-4e-06,0.43,-0.00038,0.00083,0.00032,0,0,-4.9e+02,7.7e-05,6.9e-05,0.036,0.012,0.015,0.0065,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0046,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24090000,0.71,0.0025,-0.0095,0.71,-0.1,-0.028,-0.3,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.011,0.0025,-0.13,0.21,-3.6e-06,0.43,-0.00041,0.0008,0.00036,0,0,-4.9e+02,7.8e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0046,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24190000,0.71,0.0036,-0.0072,0.71,-0.11,-0.03,-0.35,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.011,0.0024,-0.13,0.21,-2.8e-06,0.43,-0.00041,0.00083,0.00036,0,0,-4.9e+02,7.6e-05,6.8e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,4e-07,5.4e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24290000,0.71,0.0041,-0.0064,0.71,-0.12,-0.033,-0.41,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.011,0.0023,-0.13,0.21,-2.5e-06,0.43,-0.00045,0.00088,0.00042,0,0,-4.9e+02,7.7e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4e-07,5.4e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24390000,0.71,0.0042,-0.0065,0.71,-0.13,-0.041,-0.46,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.011,0.003,-0.13,0.21,2.9e-07,0.43,-0.00033,0.00092,0.00042,0,0,-4.9e+02,7.5e-05,6.7e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24490000,0.71,0.005,-0.0024,0.71,-0.14,-0.046,-0.51,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.011,0.003,-0.13,0.21,2.9e-07,0.43,-0.00033,0.00093,0.00041,0,0,-4.9e+02,7.6e-05,6.8e-05,0.036,0.013,0.016,0.0064,0.039,0.042,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24590000,0.71,0.0055,0.0013,0.71,-0.16,-0.057,-0.56,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.003,-0.13,0.21,1.4e-06,0.43,2.7e-05,0.00058,0.00036,0,0,-4.9e+02,7.4e-05,6.7e-05,0.036,0.012,0.015,0.0063,0.036,0.038,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24690000,0.71,0.0056,0.0022,0.71,-0.18,-0.07,-0.64,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.0028,-0.13,0.21,2.4e-06,0.43,-1.8e-05,0.00062,0.00054,0,0,-4.9e+02,7.5e-05,6.7e-05,0.036,0.013,0.016,0.0063,0.039,0.042,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24790000,0.71,0.0053,0.00097,0.71,-0.2,-0.083,-0.73,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.0029,-0.13,0.21,1.8e-06,0.43,1.5e-05,0.00059,0.0003,0,0,-4.9e+02,7.3e-05,6.6e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24890000,0.71,0.0071,0.0027,0.71,-0.22,-0.094,-0.75,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.0029,-0.13,0.21,2.6e-06,0.43,-9.1e-05,0.00075,0.00032,0,0,-4.9e+02,7.4e-05,6.6e-05,0.036,0.013,0.016,0.0062,0.039,0.042,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24990000,0.71,0.0089,0.0044,0.71,-0.24,-0.1,-0.81,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.0099,0.0026,-0.13,0.21,2.1e-06,0.43,-0.00017,0.00085,-2.2e-05,0,0,-4.9e+02,7.2e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.8e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25090000,0.71,0.0092,0.0038,0.71,-0.27,-0.11,-0.86,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.0098,0.0027,-0.13,0.21,1.7e-06,0.43,-0.00019,0.00086,-5.8e-05,0,0,-4.9e+02,7.3e-05,6.5e-05,0.036,0.013,0.017,0.0062,0.039,0.042,0.033,3.7e-07,4.8e-07,1.5e-06,0.0041,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25190000,0.71,0.0087,0.0024,0.71,-0.3,-0.13,-0.91,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.0092,0.003,-0.13,0.21,7.1e-06,0.43,7e-05,0.00083,7.7e-05,0,0,-4.9e+02,7.2e-05,6.4e-05,0.035,0.012,0.016,0.0061,0.036,0.038,0.033,3.6e-07,4.6e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25290000,0.71,0.011,0.0092,0.71,-0.33,-0.14,-0.96,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.0092,0.003,-0.13,0.21,6.9e-06,0.43,9.5e-05,0.00077,8.4e-05,0,0,-4.9e+02,7.2e-05,6.5e-05,0.035,0.013,0.017,0.0061,0.039,0.042,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25390000,0.71,0.012,0.016,0.71,-0.36,-0.16,-1,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.0085,0.0027,-0.13,0.21,1.1e-05,0.43,0.0005,0.00046,0.00012,0,0,-4.9e+02,7.1e-05,6.3e-05,0.035,0.012,0.016,0.006,0.036,0.038,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25490000,0.71,0.012,0.017,0.71,-0.41,-0.18,-1.1,0,0,-4.9e+02,-0.0013,-0.0058,0.00014,0.0084,0.0026,-0.13,0.21,9.7e-06,0.43,0.00067,0.00013,0.00031,0,0,-4.9e+02,7.2e-05,6.4e-05,0.035,0.013,0.018,0.006,0.039,0.042,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25590000,0.71,0.012,0.015,0.71,-0.45,-0.21,-1.1,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.0077,0.003,-0.13,0.21,1.6e-05,0.43,0.00097,0.00014,0.00032,0,0,-4.9e+02,7.1e-05,6.3e-05,0.034,0.012,0.018,0.006,0.036,0.038,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25690000,0.71,0.015,0.022,0.71,-0.49,-0.23,-1.2,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.0077,0.003,-0.13,0.21,1.6e-05,0.43,0.00096,0.00016,0.0004,0,0,-4.9e+02,7.1e-05,6.3e-05,0.034,0.013,0.02,0.006,0.039,0.042,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0014,0.0012,0.0011,1,1,0.01 +25790000,0.71,0.018,0.028,0.71,-0.54,-0.26,-1.2,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.007,0.0023,-0.13,0.21,2e-05,0.43,0.0013,-8.6e-05,-5.5e-05,0,0,-4.9e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.0059,0.036,0.038,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 +25890000,0.71,0.018,0.029,0.71,-0.62,-0.29,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00017,0.0072,0.0022,-0.13,0.21,2.2e-05,0.43,0.0014,-1.8e-05,-0.00012,0,0,-4.9e+02,7.1e-05,6.3e-05,0.033,0.014,0.022,0.006,0.039,0.042,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 +25990000,0.7,0.017,0.025,0.71,-0.67,-0.32,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00019,0.0063,0.0026,-0.13,0.21,2.9e-05,0.43,0.0023,-0.00058,-0.00058,0,0,-4.9e+02,7e-05,6.2e-05,0.032,0.013,0.021,0.0059,0.036,0.039,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 +26090000,0.7,0.022,0.035,0.71,-0.74,-0.35,-1.3,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0064,0.0027,-0.13,0.21,2.5e-05,0.43,0.0024,-0.0005,-0.0012,0,0,-4.9e+02,7.1e-05,6.2e-05,0.032,0.014,0.024,0.0059,0.039,0.043,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 +26190000,0.7,0.024,0.045,0.71,-0.79,-0.39,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00018,0.0053,0.0016,-0.13,0.21,3.9e-05,0.43,0.0023,0.0004,-0.0014,0,0,-4.9e+02,7.1e-05,6.1e-05,0.03,0.014,0.024,0.0058,0.036,0.039,0.032,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.001,0.0013,0.001,0.001,1,1,0.01 +26290000,0.7,0.025,0.047,0.71,-0.89,-0.43,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00018,0.0053,0.0016,-0.13,0.21,3.8e-05,0.43,0.0023,0.00027,-0.0014,0,0,-4.9e+02,7.1e-05,6.2e-05,0.03,0.015,0.028,0.0059,0.039,0.043,0.033,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.00099,3.9e-05,0.00099,0.0013,0.001,0.00099,1,1,0.01 +26390000,0.7,0.024,0.044,0.71,-0.96,-0.49,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00021,0.0044,0.0024,-0.13,0.21,4.6e-05,0.44,0.0036,-0.00018,-0.0024,0,0,-4.9e+02,7.1e-05,6.1e-05,0.028,0.014,0.027,0.0058,0.036,0.039,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0042,0.00014,0.00096,3.9e-05,0.00095,0.0012,0.00096,0.00095,1,1,0.01 +26490000,0.7,0.031,0.06,0.71,-1.1,-0.53,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00021,0.0044,0.0024,-0.13,0.21,3.9e-05,0.44,0.004,-0.00099,-0.0027,0,0,-4.9e+02,7.2e-05,6.1e-05,0.028,0.016,0.031,0.0058,0.039,0.044,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0042,0.00014,0.00092,3.9e-05,0.00092,0.0012,0.00092,0.00091,1,1,0.01 +26590000,0.7,0.037,0.076,0.71,-1.2,-0.59,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00019,0.0028,0.0014,-0.13,0.21,3.9e-05,0.44,0.0042,-0.00064,-0.0048,0,0,-4.9e+02,7.2e-05,6e-05,0.025,0.015,0.031,0.0058,0.036,0.04,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0041,0.00013,0.00087,3.9e-05,0.00086,0.001,0.00087,0.00086,1,1,0.01 +26690000,0.7,0.039,0.079,0.71,-1.3,-0.65,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00019,0.0028,0.0013,-0.13,0.21,4.5e-05,0.44,0.004,-0.00013,-0.004,0,0,-4.9e+02,7.2e-05,6.1e-05,0.025,0.017,0.037,0.0058,0.04,0.045,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00081,3.9e-05,0.0008,0.001,0.00081,0.00079,1,1,0.01 +26790000,0.7,0.036,0.074,0.71,-1.4,-0.74,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00022,0.0012,0.0022,-0.13,0.21,8.4e-05,0.44,0.0055,0.00063,-0.0038,0,0,-4.9e+02,7.3e-05,6e-05,0.022,0.016,0.036,0.0057,0.036,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00076,3.9e-05,0.00075,0.00092,0.00076,0.00074,1,1,0.01 +26890000,0.7,0.045,0.096,0.71,-1.6,-0.8,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00023,0.0013,0.0021,-0.13,0.21,9e-05,0.44,0.0054,0.0013,-0.0041,0,0,-4.9e+02,7.3e-05,6e-05,0.022,0.018,0.043,0.0058,0.04,0.046,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00072,3.9e-05,0.0007,0.00092,0.00072,0.0007,1,1,0.01 +26990000,0.7,0.051,0.12,0.71,-1.7,-0.89,-1.3,0,0,-4.9e+02,-0.00099,-0.0059,0.00022,-0.00069,0.00024,-0.13,0.21,0.00013,0.44,0.0061,0.0034,-0.0056,0,0,-4.9e+02,7.4e-05,6e-05,0.019,0.017,0.042,0.0057,0.037,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00065,3.9e-05,0.00063,0.00079,0.00065,0.00062,1,1,0.01 +27090000,0.7,0.052,0.12,0.71,-1.9,-0.98,-1.3,0,0,-4.9e+02,-0.00098,-0.0059,0.00022,-0.00073,0.00025,-0.13,0.21,0.00013,0.44,0.0061,0.0035,-0.0052,0,0,-4.9e+02,7.4e-05,6e-05,0.019,0.02,0.052,0.0057,0.04,0.048,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00059,3.9e-05,0.00056,0.00078,0.0006,0.00056,1,1,0.01 +27190000,0.7,0.05,0.11,0.7,-2.1,-1,-1.2,0,0,-4.9e+02,-0.00097,-0.0059,0.00022,-0.0018,6.1e-05,-0.13,0.21,4.8e-05,0.44,0.0021,0.0027,-0.0049,0,0,-4.9e+02,7.5e-05,6e-05,0.016,0.02,0.051,0.0057,0.043,0.05,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00055,3.9e-05,0.00051,0.00066,0.00055,0.00051,1,1,0.01 +27290000,0.71,0.044,0.095,0.7,-2.3,-1.1,-1.2,0,0,-4.9e+02,-0.00097,-0.0059,0.00023,-0.0018,4.3e-05,-0.13,0.21,5.6e-05,0.44,0.002,0.0034,-0.0049,0,0,-4.9e+02,7.6e-05,6.1e-05,0.016,0.022,0.059,0.0057,0.047,0.057,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00052,3.9e-05,0.00048,0.00066,0.00052,0.00048,1,1,0.01 +27390000,0.71,0.038,0.079,0.7,-2.4,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0017,-0.13,0.21,1.3e-05,0.44,-0.00049,0.0032,-0.0064,0,0,-4.9e+02,7.6e-05,6e-05,0.013,0.021,0.052,0.0057,0.049,0.059,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00049,3.9e-05,0.00046,0.00055,0.00049,0.00046,1,1,0.01 +27490000,0.71,0.032,0.064,0.7,-2.5,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0016,-0.13,0.21,1.9e-05,0.44,-0.00057,0.0032,-0.0067,0,0,-4.9e+02,7.7e-05,6.1e-05,0.013,0.023,0.056,0.0057,0.054,0.067,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00048,3.9e-05,0.00045,0.00055,0.00048,0.00044,1,1,0.01 +27590000,0.72,0.028,0.051,0.69,-2.6,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00023,-0.0037,-0.001,-0.12,0.21,-3.7e-05,0.44,-0.0032,0.0027,-0.0066,0,0,-4.9e+02,7.7e-05,6.1e-05,0.011,0.021,0.047,0.0057,0.056,0.068,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00044,1,1,0.01 +27690000,0.72,0.027,0.05,0.69,-2.6,-1.2,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00023,-0.0036,-0.00089,-0.12,0.21,-3.3e-05,0.44,-0.0033,0.0026,-0.0068,0,0,-4.9e+02,7.8e-05,6.1e-05,0.011,0.022,0.049,0.0057,0.062,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00043,1,1,0.01 +27790000,0.72,0.027,0.051,0.69,-2.6,-1.2,-1.2,0,0,-4.9e+02,-0.00091,-0.0059,0.00022,-0.0042,-0.0007,-0.12,0.21,-6e-05,0.44,-0.005,0.0021,-0.0072,0,0,-4.9e+02,7.9e-05,6.1e-05,0.0097,0.02,0.042,0.0056,0.064,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00045,3.9e-05,0.00043,0.00041,0.00045,0.00043,1,1,0.01 +27890000,0.72,0.027,0.049,0.69,-2.7,-1.2,-1.2,0,0,-4.9e+02,-0.00091,-0.0059,0.00023,-0.0042,-0.00071,-0.12,0.21,-6.1e-05,0.44,-0.005,0.002,-0.0072,0,0,-4.9e+02,7.9e-05,6.1e-05,0.0097,0.021,0.043,0.0057,0.07,0.087,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00044,3.9e-05,0.00043,0.00041,0.00044,0.00042,1,1,0.01 +27990000,0.72,0.026,0.046,0.69,-2.7,-1.2,-1.2,0,0,-4.9e+02,-0.00093,-0.0059,0.00024,-0.004,0.00022,-0.12,0.21,-7.7e-05,0.44,-0.0064,0.0015,-0.0071,0,0,-4.9e+02,8e-05,6.1e-05,0.0087,0.02,0.038,0.0056,0.072,0.087,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00043,3.9e-05,0.00042,0.00037,0.00043,0.00042,1,1,0.01 +28090000,0.72,0.032,0.059,0.69,-2.8,-1.2,-1.2,0,0,-4.9e+02,-0.00093,-0.0059,0.00023,-0.0042,0.00043,-0.12,0.21,-7.7e-05,0.44,-0.0065,0.0014,-0.0072,0,0,-4.9e+02,8.1e-05,6.1e-05,0.0086,0.021,0.039,0.0057,0.078,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00042,3.9e-05,0.00042,0.00036,0.00042,0.00041,1,1,0.01 +28190000,0.72,0.037,0.072,0.69,-2.8,-1.2,-0.94,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0042,0.00087,-0.12,0.21,-9.5e-05,0.44,-0.0073,0.00091,-0.0071,0,0,-4.9e+02,8.1e-05,6.1e-05,0.0079,0.02,0.034,0.0056,0.08,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00041,3.9e-05,0.00041,0.00033,0.00041,0.00041,1,1,0.01 +28290000,0.72,0.029,0.055,0.69,-2.8,-1.2,-0.078,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0043,0.00098,-0.12,0.21,-9.8e-05,0.44,-0.0073,0.0013,-0.0069,0,0,-4.9e+02,8.2e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.087,0.11,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28390000,0.73,0.012,0.024,0.69,-2.8,-1.2,0.78,0,0,-4.9e+02,-0.00094,-0.0059,0.00023,-0.0042,0.0013,-0.12,0.21,-8.5e-05,0.44,-0.0075,0.0014,-0.007,0,0,-4.9e+02,8.3e-05,6.2e-05,0.0079,0.02,0.035,0.0057,0.094,0.12,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28490000,0.73,0.0028,0.006,0.69,-2.8,-1.2,1.1,0,0,-4.9e+02,-0.00095,-0.0059,0.00023,-0.0039,0.0015,-0.12,0.21,-6.7e-05,0.44,-0.0076,0.0014,-0.0069,0,0,-4.9e+02,8.4e-05,6.2e-05,0.0079,0.021,0.035,0.0057,0.1,0.13,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28590000,0.73,0.00088,0.0025,0.69,-2.7,-1.2,0.97,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0039,0.0016,-0.12,0.21,-6.9e-05,0.44,-0.0075,0.0015,-0.007,0,0,-4.9e+02,8.4e-05,6.2e-05,0.0079,0.021,0.033,0.0057,0.11,0.14,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28690000,0.73,0.00018,0.0016,0.69,-2.6,-1.2,0.98,0,0,-4.9e+02,-0.00095,-0.0059,0.00024,-0.0036,0.0019,-0.12,0.21,-5.2e-05,0.44,-0.0076,0.0014,-0.0068,0,0,-4.9e+02,8.5e-05,6.2e-05,0.0079,0.022,0.033,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.00039,0.0004,1,1,0.01 +28790000,0.73,-1.6e-05,0.0015,0.69,-2.6,-1.2,0.98,0,0,-4.9e+02,-0.00098,-0.0059,0.00024,-0.0031,0.0022,-0.12,0.21,-9.3e-05,0.44,-0.0091,0.00063,-0.006,0,0,-4.9e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28890000,0.73,-6.2e-06,0.0018,0.69,-2.5,-1.2,0.97,0,0,-4.9e+02,-0.00099,-0.0059,0.00024,-0.0029,0.0025,-0.12,0.21,-7.6e-05,0.44,-0.0091,0.00059,-0.0059,0,0,-4.9e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.13,0.16,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28990000,0.73,0.00034,0.0024,0.68,-2.5,-1.1,0.97,0,0,-4.9e+02,-0.001,-0.0059,0.00025,-0.0016,0.0029,-0.12,0.21,-0.00011,0.44,-0.011,-0.00033,-0.0047,0,0,-4.9e+02,8.7e-05,6.2e-05,0.0073,0.02,0.025,0.0056,0.13,0.16,0.032,3e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.0003,0.00039,0.00039,1,1,0.01 +29090000,0.73,0.00051,0.0028,0.68,-2.4,-1.1,0.96,0,0,-4.9e+02,-0.001,-0.0059,0.00025,-0.0014,0.0033,-0.12,0.21,-9.3e-05,0.44,-0.011,-0.00039,-0.0046,0,0,-4.9e+02,8.8e-05,6.2e-05,0.0073,0.021,0.025,0.0057,0.14,0.17,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29190000,0.73,0.00076,0.0032,0.68,-2.4,-1.1,0.95,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00098,0.0034,-0.12,0.21,-0.00013,0.44,-0.011,-0.00062,-0.0042,0,0,-4.9e+02,8.8e-05,6.1e-05,0.0072,0.02,0.023,0.0056,0.14,0.17,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29290000,0.73,0.0011,0.004,0.68,-2.3,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00095,0.0038,-0.12,0.21,-0.00012,0.44,-0.011,-0.00069,-0.0041,0,0,-4.9e+02,8.9e-05,6.2e-05,0.0072,0.021,0.024,0.0056,0.14,0.18,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29390000,0.73,0.0017,0.0055,0.68,-2.3,-1.1,0.99,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00022,0.0043,-0.12,0.21,-0.00015,0.44,-0.012,-0.0014,-0.0033,0,0,-4.9e+02,8.8e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.18,0.031,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 +29490000,0.73,0.0022,0.0066,0.68,-2.3,-1.1,0.99,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00021,0.0045,-0.12,0.21,-0.00015,0.44,-0.012,-0.0013,-0.0033,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.15,0.19,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 +29590000,0.73,0.0027,0.0076,0.68,-2.2,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.00041,0.0045,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.19,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00038,1,1,0.01 +29690000,0.73,0.003,0.0082,0.68,-2.2,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00025,0.00035,0.0049,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-4.9e+02,9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29790000,0.73,0.0034,0.0087,0.68,-2.2,-1.1,0.96,0,0,-4.9e+02,-0.0012,-0.0059,0.00025,0.0014,0.0047,-0.12,0.21,-0.00018,0.44,-0.012,-0.0019,-0.0023,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29890000,0.73,0.0034,0.0088,0.68,-2.1,-1.1,0.95,0,0,-4.9e+02,-0.0012,-0.0059,0.00024,0.0011,0.0052,-0.12,0.21,-0.00018,0.44,-0.013,-0.0019,-0.0023,0,0,-4.9e+02,9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.17,0.21,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29990000,0.73,0.0036,0.0089,0.68,-2.1,-1.1,0.94,0,0,-4.9e+02,-0.0012,-0.0059,0.00022,0.0016,0.0049,-0.12,0.21,-0.0002,0.44,-0.013,-0.0021,-0.002,0,0,-4.9e+02,8.9e-05,6e-05,0.0071,0.02,0.024,0.0056,0.17,0.21,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +30090000,0.73,0.0035,0.0088,0.68,-2.1,-1.1,0.92,0,0,-4.9e+02,-0.0012,-0.0059,0.00022,0.0013,0.0052,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.18,0.22,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +30190000,0.73,0.0036,0.0085,0.68,-2.1,-1.1,0.91,0,0,-4.9e+02,-0.0012,-0.0059,0.00021,0.0021,0.0047,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-4.9e+02,8.8e-05,6e-05,0.007,0.02,0.025,0.0056,0.18,0.22,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00037,0.00038,1,1,0.01 +30290000,0.73,0.0034,0.0083,0.68,-2,-1.1,0.9,0,0,-4.9e+02,-0.0012,-0.0059,0.00021,0.0019,0.0049,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-4.9e+02,8.9e-05,6.1e-05,0.007,0.021,0.026,0.0056,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30390000,0.73,0.0035,0.008,0.68,-2,-1.1,0.89,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0027,0.0047,-0.12,0.21,-0.00022,0.43,-0.012,-0.0025,-0.0014,0,0,-4.9e+02,8.7e-05,6e-05,0.007,0.021,0.025,0.0055,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30490000,0.73,0.0034,0.0077,0.68,-2,-1.1,0.87,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0026,0.0049,-0.12,0.21,-0.00022,0.43,-0.012,-0.0024,-0.0014,0,0,-4.9e+02,8.8e-05,6e-05,0.007,0.022,0.027,0.0056,0.2,0.24,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.8e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30590000,0.73,0.0034,0.0073,0.68,-1.9,-1,0.83,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0034,0.0045,-0.12,0.21,-0.00024,0.43,-0.012,-0.0025,-0.001,0,0,-4.9e+02,8.6e-05,6e-05,0.0069,0.021,0.026,0.0055,0.2,0.24,0.031,2.8e-07,3.5e-07,1.1e-06,0.0038,0.0039,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30690000,0.73,0.0031,0.0069,0.68,-1.9,-1,0.83,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0032,0.0048,-0.12,0.21,-0.00024,0.43,-0.012,-0.0024,-0.001,0,0,-4.9e+02,8.6e-05,6e-05,0.0069,0.022,0.028,0.0055,0.21,0.25,0.031,2.8e-07,3.5e-07,1.1e-06,0.0038,0.0039,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30790000,0.73,0.0031,0.0065,0.68,-1.9,-1,0.82,0,0,-4.9e+02,-0.0012,-0.0059,0.00014,0.004,0.0042,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00079,0,0,-4.9e+02,8.4e-05,6e-05,0.0068,0.021,0.027,0.0055,0.21,0.25,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30890000,0.73,0.0029,0.006,0.68,-1.9,-1,0.81,0,0,-4.9e+02,-0.0013,-0.0059,0.00015,0.004,0.0046,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00077,0,0,-4.9e+02,8.5e-05,6e-05,0.0068,0.022,0.029,0.0055,0.22,0.26,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30990000,0.73,0.003,0.0054,0.68,-1.8,-1,0.8,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.0049,0.004,-0.12,0.21,-0.00025,0.43,-0.011,-0.0027,-0.00043,0,0,-4.9e+02,8.3e-05,6e-05,0.0067,0.021,0.028,0.0055,0.22,0.26,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.5e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31090000,0.73,0.0027,0.0049,0.68,-1.8,-1,0.79,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.0046,0.0044,-0.12,0.21,-0.00026,0.43,-0.012,-0.0027,-0.00043,0,0,-4.9e+02,8.4e-05,6e-05,0.0067,0.022,0.03,0.0055,0.23,0.27,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31190000,0.73,0.0026,0.0044,0.68,-1.8,-1,0.78,0,0,-4.9e+02,-0.0013,-0.0058,9.6e-05,0.0049,0.0044,-0.12,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00026,0,0,-4.9e+02,8.1e-05,5.9e-05,0.0066,0.021,0.028,0.0055,0.23,0.27,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31290000,0.73,0.0023,0.0039,0.68,-1.8,-1,0.78,0,0,-4.9e+02,-0.0013,-0.0058,9.9e-05,0.0047,0.0048,-0.11,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00029,0,0,-4.9e+02,8.2e-05,6e-05,0.0066,0.022,0.03,0.0055,0.24,0.28,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.3e-05,0.00036,3.8e-05,0.00038,0.00027,0.00035,0.00037,1,1,0.01 +31390000,0.73,0.0022,0.0032,0.68,-1.7,-0.99,0.78,0,0,-4.9e+02,-0.0013,-0.0058,7.7e-05,0.0051,0.0045,-0.11,0.21,-0.0003,0.43,-0.011,-0.0028,-3.3e-05,0,0,-4.9e+02,7.9e-05,5.9e-05,0.0065,0.021,0.029,0.0054,0.24,0.28,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31490000,0.73,0.0019,0.0026,0.68,-1.7,-0.99,0.78,0,0,-4.9e+02,-0.0013,-0.0058,7.3e-05,0.005,0.0051,-0.11,0.21,-0.0003,0.43,-0.011,-0.0029,3.9e-06,0,0,-4.9e+02,8e-05,5.9e-05,0.0065,0.022,0.031,0.0055,0.25,0.29,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31590000,0.73,0.002,0.0021,0.68,-1.7,-0.97,0.77,0,0,-4.9e+02,-0.0013,-0.0058,4.6e-05,0.0059,0.0047,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00024,0,0,-4.9e+02,7.8e-05,5.9e-05,0.0063,0.021,0.029,0.0054,0.25,0.29,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31690000,0.73,0.0016,0.0013,0.68,-1.6,-0.97,0.78,0,0,-4.9e+02,-0.0013,-0.0058,4.8e-05,0.0056,0.0051,-0.11,0.21,-0.0003,0.43,-0.01,-0.0029,0.00021,0,0,-4.9e+02,7.8e-05,5.9e-05,0.0063,0.022,0.031,0.0054,0.26,0.3,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31790000,0.73,0.0015,0.00056,0.69,-1.6,-0.95,0.78,0,0,-4.9e+02,-0.0013,-0.0058,2.3e-05,0.0067,0.0049,-0.11,0.21,-0.0003,0.43,-0.0097,-0.0029,0.00055,0,0,-4.9e+02,7.6e-05,5.9e-05,0.0062,0.021,0.029,0.0054,0.26,0.3,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31890000,0.73,0.0013,-0.00017,0.69,-1.6,-0.95,0.77,0,0,-4.9e+02,-0.0013,-0.0058,2.3e-05,0.0066,0.0054,-0.11,0.21,-0.00029,0.43,-0.0097,-0.0029,0.00058,0,0,-4.9e+02,7.7e-05,5.9e-05,0.0062,0.022,0.031,0.0054,0.27,0.31,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31990000,0.73,0.0012,-0.00078,0.69,-1.6,-0.93,0.77,0,0,-4.9e+02,-0.0013,-0.0058,-8e-06,0.0071,0.0053,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00075,0,0,-4.9e+02,7.4e-05,5.8e-05,0.006,0.021,0.03,0.0054,0.27,0.31,0.031,2.6e-07,2.9e-07,9.8e-07,0.0037,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32090000,0.73,0.00083,-0.0015,0.69,-1.5,-0.93,0.78,0,0,-4.9e+02,-0.0013,-0.0058,-8.9e-06,0.0069,0.0058,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00076,0,0,-4.9e+02,7.5e-05,5.9e-05,0.006,0.022,0.032,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.8e-07,0.0037,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32190000,0.73,0.00062,-0.0025,0.69,-1.5,-0.91,0.78,0,0,-4.9e+02,-0.0014,-0.0058,-4.3e-05,0.0074,0.0058,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-4.9e+02,7.3e-05,5.8e-05,0.0059,0.021,0.03,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.6e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32290000,0.73,0.00035,-0.0032,0.69,-1.5,-0.91,0.77,0,0,-4.9e+02,-0.0014,-0.0058,-4.3e-05,0.0072,0.0064,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-4.9e+02,7.3e-05,5.8e-05,0.0059,0.022,0.032,0.0054,0.29,0.33,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32390000,0.73,0.00025,-0.004,0.69,-1.5,-0.89,0.77,0,0,-4.9e+02,-0.0014,-0.0058,-6.1e-05,0.0077,0.0063,-0.11,0.2,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-4.9e+02,7.1e-05,5.8e-05,0.0057,0.021,0.03,0.0054,0.29,0.33,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32490000,0.72,0.0001,-0.0042,0.69,-1.4,-0.88,0.78,0,0,-4.9e+02,-0.0014,-0.0058,-5.9e-05,0.0075,0.0067,-0.11,0.2,-0.0003,0.43,-0.0084,-0.0031,0.0011,0,0,-4.9e+02,7.2e-05,5.8e-05,0.0057,0.022,0.032,0.0054,0.3,0.34,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32590000,0.72,0.00015,-0.0046,0.69,-1.4,-0.87,0.78,0,0,-4.9e+02,-0.0014,-0.0057,-8e-05,0.0079,0.0067,-0.11,0.21,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-4.9e+02,7e-05,5.8e-05,0.0056,0.021,0.03,0.0053,0.3,0.34,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32690000,0.72,0.00011,-0.0046,0.69,-1.4,-0.86,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-8.1e-05,0.0079,0.0071,-0.11,0.2,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-4.9e+02,7e-05,5.8e-05,0.0056,0.022,0.032,0.0053,0.31,0.35,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00036,1,1,0.01 +32790000,0.72,0.00023,-0.0047,0.69,-1.3,-0.84,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.0001,0.0082,0.0071,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0031,0.0015,0,0,-4.9e+02,6.8e-05,5.7e-05,0.0054,0.022,0.03,0.0053,0.3,0.35,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32890000,0.72,0.00031,-0.0046,0.69,-1.3,-0.84,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.0081,0.0077,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0032,0.0016,0,0,-4.9e+02,6.9e-05,5.8e-05,0.0054,0.022,0.031,0.0053,0.32,0.36,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32990000,0.72,0.00052,-0.0047,0.69,-1.3,-0.82,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.0086,0.0078,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-4.9e+02,6.7e-05,5.7e-05,0.0052,0.021,0.029,0.0053,0.31,0.36,0.03,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +33090000,0.72,0.00049,-0.0048,0.69,-1.3,-0.82,0.76,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.0085,0.0081,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-4.9e+02,6.8e-05,5.7e-05,0.0053,0.022,0.031,0.0053,0.33,0.37,0.031,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +33190000,0.72,0.0039,-0.0039,0.7,-1.2,-0.8,0.7,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.0086,0.008,-0.11,0.21,-0.0003,0.43,-0.0068,-0.0031,0.0017,0,0,-4.9e+02,6.6e-05,5.7e-05,0.0051,0.022,0.029,0.0053,0.32,0.37,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 +33290000,0.67,0.016,-0.0033,0.74,-1.2,-0.78,0.68,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.0084,0.0083,-0.11,0.2,-0.00028,0.43,-0.007,-0.0032,0.0016,0,0,-4.9e+02,6.6e-05,5.7e-05,0.0051,0.022,0.031,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0036,8.3e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 +33390000,0.56,0.014,-0.0037,0.83,-1.2,-0.77,0.88,0,0,-4.9e+02,-0.0014,-0.0057,-0.00013,0.0086,0.0086,-0.11,0.21,-0.00034,0.43,-0.0063,-0.0032,0.0018,0,0,-4.9e+02,6.5e-05,5.6e-05,0.0047,0.021,0.028,0.0053,0.33,0.38,0.031,2.4e-07,2.6e-07,8.3e-07,0.0036,0.0035,8.3e-05,0.00032,3.8e-05,0.00036,0.00021,0.00032,0.00036,1,1,0.01 +33490000,0.43,0.007,-0.0011,0.9,-1.2,-0.76,0.89,0,0,-4.9e+02,-0.0014,-0.0057,-0.00015,0.0086,0.0087,-0.11,0.21,-0.00043,0.43,-0.0058,-0.002,0.0018,0,0,-4.9e+02,6.5e-05,5.6e-05,0.0041,0.022,0.029,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.1e-07,0.0036,0.0035,8.3e-05,0.00025,3.7e-05,0.00036,0.00017,0.00024,0.00036,1,1,0.01 +33590000,0.27,0.00094,-0.0036,0.96,-1.2,-0.75,0.86,0,0,-4.9e+02,-0.0014,-0.0057,-0.00018,0.0086,0.0087,-0.11,0.21,-0.00067,0.43,-0.0038,-0.0013,0.002,0,0,-4.9e+02,6.4e-05,5.5e-05,0.0031,0.02,0.027,0.0052,0.34,0.37,0.03,2.4e-07,2.6e-07,7.9e-07,0.0036,0.0035,8.3e-05,0.00016,3.6e-05,0.00036,0.00012,0.00015,0.00036,1,1,0.01 +33690000,0.098,-0.0027,-0.0066,1,-1.1,-0.74,0.87,0,0,-4.9e+02,-0.0014,-0.0057,-0.00019,0.0086,0.0087,-0.11,0.21,-0.00072,0.43,-0.0035,-0.001,0.002,0,0,-4.9e+02,6.4e-05,5.5e-05,0.0024,0.021,0.028,0.0053,0.35,0.37,0.031,2.4e-07,2.6e-07,7.8e-07,0.0036,0.0035,8.3e-05,0.0001,3.5e-05,0.00036,8.3e-05,9.8e-05,0.00036,1,1,0.01 +33790000,-0.074,-0.0045,-0.0084,1,-1.1,-0.72,0.85,0,0,-4.9e+02,-0.0014,-0.0057,-0.00021,0.0086,0.0087,-0.11,0.21,-0.00088,0.43,-0.0021,-0.001,0.0023,0,0,-4.9e+02,6.2e-05,5.4e-05,0.0019,0.02,0.026,0.0052,0.35,0.37,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,6.8e-05,3.5e-05,0.00036,5.5e-05,6.1e-05,0.00036,1,1,0.01 +33890000,-0.24,-0.0059,-0.009,0.97,-1,-0.69,0.83,0,0,-4.9e+02,-0.0014,-0.0057,-0.00022,0.0086,0.0087,-0.11,0.21,-0.001,0.43,-0.0012,-0.0011,0.0024,0,0,-4.9e+02,6.2e-05,5.4e-05,0.0016,0.022,0.028,0.0052,0.36,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,4.8e-05,3.4e-05,0.00036,3.8e-05,4.1e-05,0.00036,1,1,0.01 +33990000,-0.39,-0.0046,-0.012,0.92,-0.94,-0.64,0.8,0,0,-4.9e+02,-0.0015,-0.0057,-0.00022,0.0086,0.0088,-0.11,0.21,-0.00098,0.43,-0.0011,-0.00064,0.0025,0,0,-4.9e+02,6e-05,5.3e-05,0.0015,0.021,0.027,0.0052,0.36,0.37,0.03,2.4e-07,2.5e-07,7.7e-07,0.0036,0.0035,8.3e-05,3.6e-05,3.4e-05,0.00036,2.8e-05,2.9e-05,0.00036,1,1,0.01 +34090000,-0.5,-0.0037,-0.014,0.87,-0.88,-0.59,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00022,0.0086,0.0091,-0.11,0.21,-0.00095,0.43,-0.0012,-0.00052,0.0025,0,0,-4.9e+02,6e-05,5.3e-05,0.0014,0.023,0.03,0.0052,0.37,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,3e-05,3.4e-05,0.00036,2.2e-05,2.3e-05,0.00036,1,1,0.01 +34190000,-0.57,-0.0037,-0.012,0.82,-0.85,-0.54,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00021,0.0064,0.012,-0.11,0.21,-0.00094,0.43,-0.001,-0.00031,0.0027,0,0,-4.9e+02,5.7e-05,5.1e-05,0.0013,0.023,0.029,0.0052,0.37,0.38,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.5e-05,3.4e-05,0.00036,1.8e-05,1.8e-05,0.00036,1,1,0.01 +34290000,-0.61,-0.0046,-0.0091,0.79,-0.8,-0.48,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00021,0.0062,0.012,-0.11,0.21,-0.00096,0.43,-0.00092,-0.00018,0.0027,0,0,-4.9e+02,5.7e-05,5.1e-05,0.0012,0.025,0.032,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.2e-05,3.4e-05,0.00036,1.5e-05,1.5e-05,0.00036,1,1,0.01 +34390000,-0.63,-0.0052,-0.0062,0.77,-0.77,-0.44,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00019,0.0034,0.016,-0.11,0.21,-0.00092,0.43,-0.00091,1.7e-05,0.0029,0,0,-4.9e+02,5.4e-05,4.9e-05,0.0012,0.025,0.031,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,2e-05,3.3e-05,0.00036,1.3e-05,1.3e-05,0.00036,1,1,0.01 +34490000,-0.65,-0.0062,-0.004,0.76,-0.72,-0.39,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00019,0.0032,0.016,-0.11,0.21,-0.00093,0.43,-0.00085,-2.4e-05,0.0029,0,0,-4.9e+02,5.4e-05,4.9e-05,0.0011,0.027,0.035,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.6e-07,0.0034,0.0035,8.1e-05,1.8e-05,3.3e-05,0.00036,1.2e-05,1.2e-05,0.00036,1,1,0.01 +34590000,-0.66,-0.0062,-0.0026,0.75,-0.7,-0.37,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,-0.0018,0.023,-0.11,0.21,-0.00088,0.43,-0.00092,3.1e-05,0.0032,0,0,-4.9e+02,5e-05,4.7e-05,0.0011,0.027,0.034,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,1.1e-05,1e-05,0.00036,1,1,0.01 +34690000,-0.67,-0.0066,-0.0018,0.75,-0.64,-0.32,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,-0.002,0.023,-0.11,0.21,-0.00091,0.43,-0.00078,0.00023,0.0031,0,0,-4.9e+02,5e-05,4.7e-05,0.0011,0.03,0.037,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,9.9e-06,9.4e-06,0.00036,1,1,0.01 +34790000,-0.67,-0.006,-0.0013,0.74,-0.63,-0.3,0.79,0,0,-4.9e+02,-0.0015,-0.0058,-0.00011,-0.008,0.03,-0.11,0.21,-0.0009,0.43,-0.00062,0.00032,0.0032,0,0,-4.9e+02,4.6e-05,4.4e-05,0.001,0.029,0.036,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,9.1e-06,8.6e-06,0.00036,1,1,0.01 +34890000,-0.67,-0.006,-0.0012,0.74,-0.57,-0.26,0.79,0,0,-4.9e+02,-0.0015,-0.0058,-0.00011,-0.0081,0.03,-0.11,0.21,-0.00089,0.43,-0.00063,0.00028,0.0033,0,0,-4.9e+02,4.6e-05,4.4e-05,0.001,0.032,0.04,0.0052,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,8.4e-06,7.9e-06,0.00036,1,1,0.01 +34990000,-0.67,-0.013,-0.0037,0.74,0.47,0.35,-0.043,0,0,-4.9e+02,-0.0016,-0.0058,-6.8e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00051,0.00034,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.001,0.034,0.046,0.0054,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.3e-05,3.3e-05,0.00036,8e-06,7.4e-06,0.00036,1,1,0.01 +35090000,-0.67,-0.013,-0.0037,0.74,0.6,0.39,-0.1,0,0,-4.9e+02,-0.0016,-0.0058,-6.9e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00047,0.00028,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00099,0.037,0.051,0.0055,0.42,0.43,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.2e-05,3.3e-05,0.00036,7.5e-06,6.9e-06,0.00036,1,1,0.01 +35190000,-0.67,-0.013,-0.0038,0.74,0.63,0.43,-0.1,0,0,-4.9e+02,-0.0016,-0.0058,-7e-05,-0.016,0.039,-0.11,0.21,-0.00088,0.43,-0.00041,0.00032,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00099,0.041,0.055,0.0055,0.43,0.44,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.2e-05,3.3e-05,0.00036,7.1e-06,6.4e-06,0.00036,1,1,0.01 +35290000,-0.67,-0.013,-0.0038,0.74,0.66,0.47,-0.099,0,0,-4.9e+02,-0.0016,-0.0058,-7.1e-05,-0.016,0.039,-0.11,0.21,-0.00089,0.43,-0.00033,0.00032,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00098,0.044,0.06,0.0055,0.44,0.45,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.8e-06,6.1e-06,0.00036,1,1,0.01 +35390000,-0.67,-0.013,-0.0038,0.74,0.69,0.51,-0.096,0,0,-4.9e+02,-0.0016,-0.0058,-7.4e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00023,0.0003,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00098,0.048,0.064,0.0055,0.46,0.47,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.5e-06,5.8e-06,0.00036,1,1,0.01 +35490000,-0.67,-0.013,-0.0038,0.74,0.73,0.56,-0.095,0,0,-4.9e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00014,0.00025,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00097,0.053,0.069,0.0055,0.47,0.48,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.2e-06,5.5e-06,0.00036,1,1,0.01 +35590000,-0.67,-0.013,-0.0038,0.74,0.76,0.6,-0.094,0,0,-4.9e+02,-0.0016,-0.0058,-7.5e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00017,0.00025,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00097,0.057,0.075,0.0055,0.49,0.5,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6e-06,5.2e-06,0.00036,1,1,0.01 +35690000,-0.67,-0.013,-0.0038,0.74,0.79,0.64,-0.092,0,0,-4.9e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-9.2e-05,0.00024,0.0036,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.062,0.08,0.0056,0.51,0.52,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0032,8e-05,1e-05,3.3e-05,0.00036,5.8e-06,5e-06,0.00036,1,1,0.01 +35790000,-0.67,-0.013,-0.0038,0.74,0.82,0.68,-0.089,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-6.8e-05,0.00024,0.0036,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.067,0.086,0.0056,0.53,0.54,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0032,8e-05,1e-05,3.3e-05,0.00036,5.6e-06,4.8e-06,0.00036,1,1,0.023 +35890000,-0.67,-0.013,-0.0039,0.74,0.85,0.72,-0.086,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00094,0.43,-5.3e-05,0.00022,0.0037,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.072,0.092,0.0056,0.55,0.56,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.4e-06,4.6e-06,0.00036,1,1,0.048 +35990000,-0.67,-0.013,-0.0038,0.74,0.88,0.76,-0.083,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-7.8e-05,0.00021,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.078,0.099,0.0056,0.57,0.59,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.9e-06,3.3e-05,0.00036,5.3e-06,4.5e-06,0.00036,1,1,0.073 +36090000,-0.68,-0.013,-0.0038,0.74,0.91,0.81,-0.079,0,0,-4.9e+02,-0.0016,-0.0058,-7.9e-05,-0.016,0.039,-0.11,0.21,-0.00094,0.43,-4.3e-05,0.00019,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.083,0.11,0.0056,0.6,0.62,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.7e-06,3.3e-05,0.00036,5.2e-06,4.3e-06,0.00036,1,1,0.099 +36190000,-0.68,-0.013,-0.0038,0.74,0.94,0.85,-0.075,0,0,-4.9e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,5.5e-05,0.00018,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.089,0.11,0.0056,0.63,0.65,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.5e-06,3.3e-05,0.00036,5e-06,4.2e-06,0.00036,1,1,0.12 +36290000,-0.68,-0.013,-0.0038,0.74,0.97,0.89,-0.07,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.016,0.039,-0.11,0.21,-0.00096,0.43,7.5e-05,0.00018,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.096,0.12,0.0056,0.66,0.68,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.4e-06,3.3e-05,0.00036,4.9e-06,4.1e-06,0.00036,1,1,0.15 +36390000,-0.68,-0.013,-0.0038,0.74,1,0.93,-0.067,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.016,0.039,-0.11,0.21,-0.00096,0.43,7.2e-05,0.00022,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.1,0.13,0.0056,0.69,0.72,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.3e-06,3.3e-05,0.00036,4.8e-06,3.9e-06,0.00036,1,1,0.17 +36490000,-0.68,-0.013,-0.0038,0.74,1,0.97,-0.063,0,0,-4.9e+02,-0.0016,-0.0058,-8.3e-05,-0.015,0.039,-0.11,0.21,-0.00095,0.43,4.2e-05,0.00023,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.11,0.13,0.0056,0.72,0.76,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.2e-06,3.3e-05,0.00036,4.7e-06,3.8e-06,0.00036,1,1,0.2 +36590000,-0.68,-0.013,-0.0038,0.74,1.1,1,-0.057,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,9e-05,0.00025,0.0037,0,0,-4.9e+02,4.3e-05,4.3e-05,0.00096,0.12,0.14,0.0056,0.76,0.8,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.1e-06,3.3e-05,0.00036,4.6e-06,3.7e-06,0.00036,1,1,0.23 +36690000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.053,0,0,-4.9e+02,-0.0016,-0.0058,-8.8e-05,-0.015,0.039,-0.11,0.21,-0.00097,0.43,0.00012,0.00027,0.0037,0,0,-4.9e+02,4.3e-05,4.3e-05,0.00096,0.12,0.15,0.0057,0.8,0.85,0.032,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9e-06,3.3e-05,0.00036,4.6e-06,3.6e-06,0.00036,1,1,0.25 +36790000,-0.68,-0.013,-0.0037,0.74,1.1,1.1,-0.047,0,0,-4.9e+02,-0.0016,-0.0058,-9.1e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00017,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.13,0.16,0.0057,0.84,0.9,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.9e-06,3.3e-05,0.00036,4.5e-06,3.5e-06,0.00036,1,1,0.28 +36890000,-0.68,-0.013,-0.0037,0.74,1.2,1.1,-0.042,0,0,-4.9e+02,-0.0016,-0.0058,-9.4e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00021,0.00022,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.14,0.17,0.0056,0.89,0.95,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.8e-06,3.3e-05,0.00036,4.4e-06,3.4e-06,0.00036,1,1,0.3 +36990000,-0.68,-0.013,-0.0037,0.74,1.2,1.2,-0.037,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00023,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,0.94,1,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.7e-06,3.3e-05,0.00036,4.3e-06,3.4e-06,0.00036,1,1,0.33 +37090000,-0.68,-0.013,-0.0036,0.74,1.2,1.2,-0.031,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00023,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,1,1.1,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.7e-05,8.6e-06,3.3e-05,0.00036,4.3e-06,3.3e-06,0.00036,1,1,0.35 +37190000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.025,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00023,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.16,0.19,0.0057,1.1,1.1,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.6e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00036,1,1,0.38 +37290000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.02,0,0,-4.9e+02,-0.0016,-0.0058,-9.8e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00024,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.4e-05,0.00096,0.17,0.2,0.0057,1.1,1.2,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.41 +37390000,-0.68,-0.013,-0.0036,0.74,1.3,1.4,-0.015,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00027,0.00027,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.18,0.21,0.0057,1.2,1.3,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3.1e-06,0.00035,1,1,0.43 +37490000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0093,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.001,0.43,0.0003,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.19,0.22,0.0057,1.3,1.4,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3e-06,0.00035,1,1,0.46 +37590000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0027,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00032,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.2,0.23,0.0057,1.3,1.5,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.3e-06,3.3e-05,0.00036,4e-06,3e-06,0.00035,1,1,0.48 +37690000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,0.0046,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00033,0.00029,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.21,0.24,0.0057,1.4,1.6,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.51 +37790000,-0.68,-0.013,-0.0036,0.74,1.5,1.5,0.012,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00034,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.22,0.26,0.0056,1.5,1.7,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.54 +37890000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.017,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-4.9e+02,4.5e-05,4.5e-05,0.00096,0.23,0.27,0.0056,1.6,1.8,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.56 +37990000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.025,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.24,0.28,0.0056,1.7,1.9,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.59 +38090000,-0.68,-0.013,-0.0036,0.74,1.5,1.7,0.034,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00037,0.0003,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.25,0.29,0.0056,1.8,2,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.61 +38190000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.04,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.26,0.3,0.0056,1.9,2.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.64 +38290000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.046,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00028,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.27,0.31,0.0056,2.1,2.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.67 +38390000,-0.68,-0.013,-0.0035,0.74,1.6,1.8,0.052,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.036,-0.11,0.21,-0.001,0.43,0.00037,0.00029,0.0037,0,0,-4.9e+02,4.6e-05,4.6e-05,0.00096,0.28,0.33,0.0056,2.2,2.5,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.69 +38490000,-0.68,-0.013,-0.0035,0.74,1.7,1.8,0.058,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.036,-0.11,0.21,-0.001,0.43,0.00038,0.00031,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.29,0.34,0.0056,2.3,2.6,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.72 +38590000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.063,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00032,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.3,0.35,0.0056,2.5,2.8,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.6e-06,0.00035,1,1,0.75 +38690000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.069,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00039,0.00034,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.31,0.36,0.0056,2.6,3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.77 +38790000,-0.68,-0.013,-0.0034,0.74,1.8,1.9,0.075,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00033,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.33,0.38,0.0056,2.8,3.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.8 +38890000,-0.68,-0.014,-0.0035,0.74,1.8,2,0.57,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00031,0.0038,0,0,-4.9e+02,4.8e-05,4.7e-05,0.00097,0.33,0.39,0.0056,3,3.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.7e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.83 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index a63e88ee9de4..b9bbada6df04 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.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.032 -90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.058 -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,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.082 -290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.095,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.11 -390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.095,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.13 -490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.16 -590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.18 -690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.095,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.21 -790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.23 -890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.095,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.26 -990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,4.9e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.095,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.28 -1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.095,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.31 -1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.6e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 -1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 -1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.2e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -1590000,1,-0.012,-0.014,0.0004,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.012,-0.014,0.00045,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.4e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-2.9e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.095,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,0.00041,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0013,-3.6e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 -2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,0.00039,0.033,-0.014,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.7e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.095,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,0.00039,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.5e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.095,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,0.0004,0.029,-0.01,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.095,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.014,0.00048,0.033,-0.0091,-0.14,0.011,-0.0043,-0.079,-0.0017,-0.0023,-1.4e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.01,-0.013,0.0004,0.023,-0.0062,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.095,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.01,-0.013,0.00044,0.027,-0.0055,-0.15,0.0091,-0.003,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.01,-0.013,0.00038,0.022,-0.0032,-0.14,0.0059,-0.0017,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.01,-0.013,0.00031,0.026,-0.005,-0.14,0.0082,-0.0021,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.01,-0.013,0.00033,0.02,-0.0039,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,-3e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.095,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.01,-0.013,0.00053,0.025,-0.0068,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,-3e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.01,-0.013,0.00058,0.02,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.095,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.01,-0.013,0.0006,0.023,-0.0067,-0.15,0.0073,-0.0021,-0.11,-0.0021,-0.0036,-3.4e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.095,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.0098,-0.013,0.00061,0.019,-0.0036,-0.15,0.0049,-0.0014,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.095,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.0097,-0.013,0.0006,0.025,-0.0023,-0.15,0.0072,-0.0017,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.095,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.0095,-0.012,0.00056,0.021,-0.0018,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.095,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.0095,-0.013,0.00054,0.024,-0.0011,-0.15,0.0074,-0.0012,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.095,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.0094,-0.012,0.00057,0.019,0.0033,-0.15,0.0051,-0.00056,-0.11,-0.0022,-0.0043,-4.7e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.095,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.0094,-0.013,0.00065,0.021,0.0046,-0.14,0.0072,-0.00017,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.095,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.0094,-0.013,0.00072,0.026,0.0042,-0.14,0.0096,0.00021,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.095,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.0093,-0.012,0.00078,0.022,0.0037,-0.12,0.0071,0.00045,-0.098,-0.0022,-0.0044,-5.1e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.095,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.0094,-0.012,0.00075,0.024,0.0034,-0.12,0.0094,0.0008,-0.1,-0.0022,-0.0044,-5.1e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.095,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.0095,-0.012,0.00076,0.021,0.0033,-0.12,0.0068,0.00069,-0.11,-0.0022,-0.0046,-5.6e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.095,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.0094,-0.012,0.00072,0.025,0.0018,-0.11,0.0091,0.00086,-0.094,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.095,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.0094,-0.012,0.00078,0.021,0.0036,-0.11,0.0067,0.00072,-0.095,-0.0022,-0.0048,-6.1e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.095,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.0094,-0.012,0.00085,0.023,0.0024,-0.11,0.0089,0.001,-0.098,-0.0022,-0.0048,-6.1e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.095,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.0094,-0.012,0.00079,0.017,0.0027,-0.1,0.0064,0.00075,-0.09,-0.0021,-0.005,-6.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.095,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.0093,-0.012,0.00089,0.015,0.0048,-0.099,0.008,0.0012,-0.092,-0.0021,-0.005,-6.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.095,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.0093,-0.012,0.00093,0.01,0.0024,-0.093,0.0053,0.0009,-0.088,-0.0021,-0.0051,-6.9e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.095,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.0092,-0.012,0.00091,0.013,0.0031,-0.085,0.0065,0.0012,-0.083,-0.0021,-0.0051,-6.9e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.0091,-0.011,0.00099,0.01,0.0034,-0.082,0.0045,0.00088,-0.082,-0.0021,-0.0052,-7.2e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.0089,-0.012,0.001,0.0099,0.007,-0.08,0.0055,0.0014,-0.079,-0.0021,-0.0052,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0071,-0.068,0.0038,0.0013,-0.072,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0021,-0.067,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.002,-0.065,-0.002,-0.0054,-7.7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0033,-0.058,-0.002,-0.0054,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0089,-0.011,0.00093,0.0077,0.016,-0.052,0.0028,0.0029,-0.055,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0088,-0.011,0.00088,0.0089,0.018,-0.049,0.0036,0.0046,-0.053,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0088,-0.011,0.00092,0.0095,0.015,-0.048,0.0027,0.0037,-0.056,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0088,-0.012,0.00089,0.011,0.017,-0.041,0.0038,0.0053,-0.05,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0088,-0.011,0.00071,0.011,0.018,-0.039,0.0049,0.0071,-0.047,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0089,-0.011,0.00072,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0089,-0.011,0.00075,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0089,-0.011,0.00076,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0018,-0.0056,-8.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0089,-0.011,0.00066,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.0089,-0.011,0.00059,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0088,-0.011,0.00055,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,1,-0.0089,-0.011,0.00052,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6890000,1,-0.0087,-0.011,0.00043,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,0.98,-0.0067,-0.012,0.18,0.0025,0.011,-0.037,0.0023,0.0048,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,0.095,0.0012,0.0012,0.054,0.16,0.17,0.031,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 -7090000,0.98,-0.0065,-0.012,0.18,0.00012,0.018,-0.038,0.0014,0.0074,-0.056,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,0.095,0.0013,0.0013,0.048,0.18,0.19,0.03,0.13,0.13,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 -7190000,0.98,-0.0065,-0.012,0.18,-5.8e-05,0.019,-0.037,0.0016,0.0091,-0.058,-0.0016,-0.0056,-9.2e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.7e-06,0,0,0.095,0.0013,0.0013,0.046,0.21,0.21,0.029,0.16,0.16,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 -7290000,0.98,-0.0064,-0.012,0.18,-0.00067,0.024,-0.034,0.00055,0.012,-0.054,-0.0016,-0.0057,-9.2e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,0.095,0.0014,0.0013,0.044,0.24,0.24,0.028,0.19,0.19,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7390000,0.98,-0.0063,-0.012,0.18,-0.0015,0.00094,-0.032,0.00016,0.014,-0.052,-0.0017,-0.0057,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-5.7e-05,0.43,-0.00048,-0.0004,8.8e-05,0,0,0.095,0.0014,0.0014,0.043,25,25,0.027,1e+02,1e+02,0.064,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00027,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7490000,0.98,-0.0063,-0.012,0.18,0.00097,0.0035,-0.026,0.00016,0.014,-0.046,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-4.5e-05,0.43,-0.00042,-0.00038,-7.9e-05,0,0,0.095,0.0015,0.0014,0.043,25,25,0.026,1e+02,1e+02,0.063,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00022,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7590000,0.98,-0.0064,-0.012,0.18,0.0021,0.006,-0.023,0.00032,0.014,-0.041,-0.0017,-0.0056,-9e-05,-0.00036,0.00036,-0.13,0.2,-3.8e-05,0.43,-0.00034,-0.00039,-9.5e-06,0,0,0.095,0.0015,0.0015,0.042,25,25,0.025,51,51,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00019,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7690000,0.98,-0.0064,-0.013,0.18,0.0021,0.0093,-0.022,0.00055,0.015,-0.036,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-3.4e-05,0.43,-0.00031,-0.0004,2.5e-06,0,0,0.095,0.0016,0.0015,0.042,25,25,0.025,52,52,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00017,0.0013,0.0014,0.0016,0.0013,1,1,2 -7790000,0.98,-0.0064,-0.013,0.18,0.0056,0.01,-0.025,0.00093,0.015,-0.041,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.9e-05,0.43,-0.00021,-0.00039,-1.5e-06,0,0,0.095,0.0016,0.0016,0.042,24,24,0.024,35,35,0.061,6.3e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00015,0.0013,0.0014,0.0016,0.0013,1,1,2 -7890000,0.98,-0.0065,-0.013,0.18,0.0046,0.014,-0.025,0.0013,0.017,-0.045,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.6e-05,0.43,-0.00019,-0.0004,4.4e-05,0,0,0.095,0.0016,0.0016,0.042,24,24,0.023,36,36,0.06,6.3e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00013,0.0013,0.0014,0.0016,0.0013,1,1,2 -7990000,0.98,-0.0063,-0.013,0.18,0.0032,0.017,-0.022,0.00098,0.017,-0.042,-0.0016,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-2.5e-05,0.43,-0.0002,-0.00042,7.4e-05,0,0,0.095,0.0017,0.0016,0.042,24,24,0.022,28,28,0.059,6.2e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00012,0.0013,0.0014,0.0016,0.0013,1,1,2 -8090000,0.98,-0.0063,-0.013,0.18,0.0043,0.019,-0.022,0.0013,0.019,-0.044,-0.0016,-0.0056,-9.4e-05,-0.00036,0.00036,-0.13,0.2,-2.2e-05,0.43,-0.00017,-0.00042,9.9e-05,0,0,0.095,0.0017,0.0017,0.042,24,24,0.022,30,30,0.059,6.2e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,0.00011,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8190000,0.98,-0.0064,-0.012,0.18,0.0052,0.022,-0.018,0.0015,0.019,-0.038,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.44,-0.00014,-0.00041,0.00014,0,0,0.095,0.0018,0.0017,0.041,23,23,0.021,24,24,0.058,6.1e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,0.0001,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8290000,0.98,-0.0062,-0.012,0.18,0.002,0.028,-0.017,0.0003,0.022,-0.038,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.43,-0.00014,-0.00044,6.7e-05,0,0,0.095,0.0018,0.0017,0.041,23,23,0.02,27,27,0.057,6.1e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,9.6e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8390000,0.98,-0.0062,-0.012,0.18,-0.0023,0.028,-0.016,-0.00016,0.022,-0.036,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00044,2.1e-05,0,0,0.095,0.0019,0.0018,0.041,21,21,0.02,23,23,0.057,6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8490000,0.98,-0.0059,-0.012,0.18,-0.0061,0.035,-0.017,-0.0015,0.026,-0.041,-0.0017,-0.0059,-9.6e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00048,-7.4e-06,0,0,0.095,0.0019,0.0018,0.041,21,21,0.019,25,25,0.056,5.9e-05,5.6e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8590000,0.98,-0.006,-0.012,0.18,-0.00034,0.034,-0.012,0.00033,0.026,-0.036,-0.0016,-0.0057,-9.6e-05,-0.00036,0.00036,-0.14,0.2,-1.7e-05,0.43,-0.00018,-0.00043,3.3e-06,0,0,0.095,0.0019,0.0018,0.041,19,19,0.018,22,22,0.055,5.8e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,7.9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8690000,0.98,-0.006,-0.012,0.18,-0.0022,0.037,-0.014,-0.00034,0.03,-0.038,-0.0016,-0.0058,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-1.6e-05,0.43,-0.00022,-0.00045,-8.7e-05,0,0,0.095,0.002,0.0018,0.041,19,19,0.018,24,24,0.055,5.8e-05,5.3e-05,2.2e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8790000,0.98,-0.006,-0.012,0.18,-0.005,0.039,-0.014,-0.0023,0.033,-0.035,-0.0016,-0.0058,-9.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00019,-0.00045,-0.00013,0,0,0.095,0.002,0.0018,0.041,19,19,0.018,27,27,0.055,5.7e-05,5.2e-05,2.2e-06,0.04,0.04,0.00099,0.0013,7.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8890000,0.98,-0.006,-0.012,0.18,0.00054,0.041,-0.0093,0.00054,0.033,-0.029,-0.0016,-0.0057,-9.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00026,-0.00043,-0.00011,0,0,0.095,0.002,0.0018,0.041,17,17,0.017,24,24,0.054,5.6e-05,5e-05,2.2e-06,0.04,0.04,0.00094,0.0013,6.7e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 -8990000,0.98,-0.0059,-0.013,0.18,0.01,0.047,-0.0085,0.0062,0.038,-0.032,-0.0017,-0.0056,-8.9e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00037,-0.00039,-6.6e-05,0,0,0.095,0.0021,0.0018,0.041,17,17,0.017,27,27,0.054,5.5e-05,4.9e-05,2.2e-06,0.04,0.04,0.00091,0.0013,6.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 -9090000,0.98,-0.0055,-0.012,0.18,-0.00032,0.056,-0.0095,0.00069,0.041,-0.032,-0.0018,-0.0057,-8.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00028,-0.00049,-8.8e-05,0,0,0.095,0.0021,0.0018,0.041,15,15,0.016,24,24,0.053,5.3e-05,4.7e-05,2.2e-06,0.04,0.04,0.00087,0.0013,6.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 -9190000,0.98,-0.0053,-0.013,0.18,0.0029,0.064,-0.0089,0.00089,0.049,-0.032,-0.0018,-0.0057,-8.6e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00031,-0.00053,-0.00011,0,0,0.095,0.0021,0.0018,0.041,15,15,0.016,27,27,0.052,5.2e-05,4.5e-05,2.2e-06,0.04,0.04,0.00083,0.0013,5.9e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.3 -9290000,0.98,-0.0053,-0.013,0.18,0.013,0.062,-0.0074,0.0055,0.046,-0.03,-0.0018,-0.0056,-8.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.0004,-0.00049,-8.5e-05,0,0,0.095,0.0021,0.0018,0.041,13,13,0.015,24,24,0.052,5.1e-05,4.4e-05,2.2e-06,0.04,0.04,0.00079,0.0013,5.6e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 -9390000,0.98,-0.0054,-0.013,0.18,0.014,0.06,-0.0062,0.0071,0.049,-0.03,-0.0017,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00035,-0.00043,-3.8e-05,0,0,0.095,0.0021,0.0018,0.041,13,13,0.015,26,26,0.052,5e-05,4.2e-05,2.2e-06,0.04,0.04,0.00077,0.0013,5.4e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 -9490000,0.98,-0.0053,-0.013,0.18,0.0087,0.061,-0.0045,0.0044,0.048,-0.027,-0.0018,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00033,-0.00048,-7.6e-05,0,0,0.095,0.0021,0.0018,0.041,12,12,0.015,23,23,0.051,4.8e-05,4e-05,2.2e-06,0.04,0.04,0.00074,0.0013,5.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 -9590000,0.98,-0.0057,-0.013,0.18,0.0078,0.052,-0.0045,0.0046,0.048,-0.029,-0.0016,-0.0057,-9.3e-05,-0.00036,0.00036,-0.14,0.2,-1e-05,0.43,-0.00031,-0.00041,-0.00012,0,0,0.095,0.0022,0.0018,0.041,12,12,0.014,26,26,0.05,4.7e-05,3.9e-05,2.2e-06,0.04,0.04,0.00071,0.0013,5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 -9690000,0.98,-0.0059,-0.013,0.18,0.0096,0.047,-0.0016,0.0057,0.043,-0.027,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-9.2e-06,0.43,-0.00031,-0.00037,-9.9e-05,0,0,0.095,0.0022,0.0018,0.041,10,10,0.014,23,23,0.05,4.6e-05,3.7e-05,2.2e-06,0.04,0.04,0.00068,0.0013,4.8e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -9790000,0.98,-0.0061,-0.012,0.18,0.001,0.041,-0.003,0.00039,0.042,-0.028,-0.0015,-0.0058,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.7e-06,0.43,-0.00018,-0.00036,-0.00015,0,0,0.095,0.0022,0.0017,0.041,10,10,0.014,25,25,0.05,4.4e-05,3.5e-05,2.2e-06,0.04,0.04,0.00066,0.0013,4.7e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -9890000,0.98,-0.0061,-0.012,0.18,0.0086,0.04,-0.0016,0.0039,0.04,-0.029,-0.0015,-0.0057,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.6e-06,0.43,-0.00023,-0.00034,-9.4e-05,0,0,0.095,0.0022,0.0017,0.041,8.6,8.7,0.013,22,22,0.049,4.3e-05,3.4e-05,2.2e-06,0.04,0.04,0.00063,0.0013,4.5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -9990000,0.98,-0.0063,-0.012,0.18,0.0025,0.034,-0.00096,-0.0002,0.039,-0.031,-0.0014,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-6.4e-06,0.43,-0.00014,-0.00033,-0.00013,0,0,0.095,0.0022,0.0017,0.041,8.6,8.7,0.013,24,24,0.049,4.2e-05,3.2e-05,2.2e-06,0.04,0.04,0.00061,0.0013,4.4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -10090000,0.98,-0.0067,-0.012,0.18,0.00073,0.019,0.00023,0.00018,0.03,-0.029,-0.0013,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-4.9e-06,0.43,-9.7e-05,-0.00025,-0.00015,0,0,0.095,0.0022,0.0017,0.041,7.4,7.5,0.013,21,21,0.048,4e-05,3.1e-05,2.2e-06,0.04,0.04,0.00059,0.0013,4.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10190000,0.98,-0.0072,-0.012,0.18,0.0053,0.0047,0.0011,0.0043,0.022,-0.03,-0.0011,-0.0058,-0.00012,-0.00036,0.00036,-0.14,0.2,-3.3e-06,0.43,-9.1e-05,-0.00012,-0.00015,0,0,0.095,0.0022,0.0016,0.041,7.4,7.6,0.012,23,23,0.048,3.9e-05,2.9e-05,2.2e-06,0.04,0.04,0.00057,0.0013,4.1e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10290000,0.98,-0.0071,-0.012,0.18,0.012,0.0085,3e-05,0.008,0.023,-0.029,-0.0012,-0.0057,-0.00011,-0.00036,0.00036,-0.14,0.2,-3.7e-06,0.43,-0.00016,-0.00011,-0.00012,0,0,0.095,0.0022,0.0016,0.041,6.4,6.5,0.012,20,20,0.048,3.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10390000,0.98,-0.0071,-0.012,0.18,0.0076,0.0026,-0.0025,0.00078,3e-05,-0.028,-0.0012,-0.0056,-0.00011,-0.0003,0.00041,-0.14,0.2,-3.9e-06,0.43,-0.0002,-0.00011,-6.5e-05,0,0,0.095,0.0022,0.0016,0.041,0.25,0.25,0.56,0.25,0.25,0.048,3.6e-05,2.7e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10490000,0.98,-0.0073,-0.012,0.18,0.0096,0.00082,0.007,0.0016,0.00011,-0.023,-0.0011,-0.0057,-0.00011,-0.00033,0.00027,-0.14,0.2,-3e-06,0.43,-0.00016,-5.9e-05,-8.7e-05,0,0,0.095,0.0021,0.0016,0.041,0.25,0.26,0.55,0.26,0.26,0.057,3.5e-05,2.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10590000,0.98,-0.007,-0.012,0.18,0.00028,-0.00036,0.013,-0.0011,-0.0055,-0.021,-0.0012,-0.0056,-0.00011,-0.0003,0.00025,-0.14,0.2,-3.6e-06,0.43,-0.00018,-9.8e-05,-7.3e-05,0,0,0.095,0.0021,0.0015,0.041,0.13,0.13,0.27,0.13,0.13,0.055,3.3e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10690000,0.98,-0.0071,-0.013,0.18,0.0031,-0.0029,0.016,-0.0009,-0.0057,-0.018,-0.0011,-0.0056,-0.00011,-0.00027,0.00018,-0.14,0.2,-3.3e-06,0.43,-0.00021,-4.9e-05,-7e-05,0,0,0.095,0.0021,0.0015,0.041,0.13,0.14,0.26,0.14,0.14,0.065,3.2e-05,2.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10790000,0.98,-0.0073,-0.013,0.18,0.0057,-0.0061,0.014,-0.00055,-0.005,-0.015,-0.0011,-0.0056,-0.00011,-0.00016,7.3e-05,-0.14,0.2,-3.1e-06,0.43,-0.00026,1.3e-05,-9e-05,0,0,0.095,0.002,0.0014,0.041,0.09,0.094,0.17,0.09,0.09,0.061,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10890000,0.98,-0.0069,-0.013,0.18,0.008,-0.003,0.0099,0.00021,-0.0052,-0.018,-0.0012,-0.0055,-0.00011,-5.5e-05,0.0002,-0.14,0.2,-4.1e-06,0.43,-0.00033,-3e-05,-7.2e-05,0,0,0.095,0.002,0.0014,0.041,0.096,0.1,0.16,0.096,0.096,0.068,2.9e-05,2e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -10990000,0.98,-0.0069,-0.013,0.18,0.0054,0.0031,0.016,-0.00022,-0.0036,-0.012,-0.0012,-0.0056,-0.00011,-0.00021,0.00015,-0.14,0.2,-4.1e-06,0.43,-0.00026,-5.9e-05,-0.00012,0,0,0.095,0.0019,0.0014,0.041,0.074,0.081,0.12,0.072,0.072,0.065,2.6e-05,1.9e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11090000,0.98,-0.0075,-0.013,0.18,0.0093,0.0016,0.019,0.00071,-0.0039,-0.0075,-0.0011,-0.0056,-0.00011,-0.0003,-5.7e-05,-0.14,0.2,-2.9e-06,0.43,-0.00024,2.4e-05,-0.0001,0,0,0.095,0.0019,0.0013,0.041,0.081,0.092,0.11,0.078,0.078,0.069,2.6e-05,1.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11190000,0.98,-0.0077,-0.013,0.18,0.0082,0.0022,0.026,0.0013,-0.0032,-0.00047,-0.001,-0.0056,-0.00012,-0.00042,-1.2e-05,-0.14,0.2,-2.4e-06,0.43,-0.00017,-1.3e-06,-0.00012,0,0,0.095,0.0017,0.0013,0.04,0.066,0.075,0.084,0.062,0.062,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11290000,0.98,-0.0077,-0.012,0.18,0.0065,-0.00037,0.025,0.0016,-0.0032,-0.00025,-0.001,-0.0057,-0.00012,-0.00052,0.00011,-0.14,0.2,-2.2e-06,0.43,-0.0001,-4e-05,-0.00015,0,0,0.095,0.0017,0.0012,0.04,0.074,0.088,0.078,0.067,0.068,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11390000,0.98,-0.0076,-0.012,0.18,0.0045,0.00076,0.016,0.0009,-0.0025,-0.0086,-0.001,-0.0057,-0.00012,-0.00055,1.9e-05,-0.14,0.2,-2.3e-06,0.43,-7.8e-05,-5.1e-05,-0.00018,0,0,0.095,0.0015,0.0012,0.04,0.062,0.073,0.064,0.056,0.056,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11490000,0.98,-0.0075,-0.012,0.18,0.0052,-0.00076,0.02,0.0016,-0.0025,-0.0026,-0.001,-0.0057,-0.00012,-0.00053,-6.4e-05,-0.14,0.2,-2.3e-06,0.43,-0.0001,-3e-05,-0.00017,0,0,0.095,0.0015,0.0011,0.04,0.07,0.086,0.058,0.061,0.062,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11590000,0.98,-0.0076,-0.012,0.18,0.0047,-0.00067,0.018,0.00077,-0.002,-0.0037,-0.001,-0.0058,-0.00012,-0.00061,2.7e-05,-0.14,0.2,-2.3e-06,0.43,-5e-05,-7e-05,-0.00019,0,0,0.095,0.0014,0.0011,0.04,0.06,0.072,0.049,0.052,0.052,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11690000,0.98,-0.0075,-0.012,0.18,0.0041,0.0017,0.018,0.00093,-0.0018,-0.0051,-0.0011,-0.0058,-0.00012,-0.00057,0.00015,-0.14,0.2,-2.5e-06,0.43,-4.4e-05,-8.6e-05,-0.00022,0,0,0.095,0.0014,0.001,0.04,0.068,0.084,0.046,0.058,0.059,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11790000,0.98,-0.0075,-0.012,0.18,0.0028,0.0026,0.019,0.00044,-0.0024,-0.0021,-0.0011,-0.0058,-0.00012,-4.6e-05,0.00011,-0.14,0.2,-2.6e-06,0.43,-5.7e-05,-9.1e-05,-0.00022,0,0,0.095,0.0012,0.00096,0.039,0.058,0.07,0.039,0.049,0.05,0.062,1.2e-05,9.4e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11890000,0.98,-0.0077,-0.012,0.18,0.0039,0.0012,0.017,0.0003,-0.0026,-0.0015,-0.0011,-0.0058,-0.00012,-0.00025,0.00027,-0.14,0.2,-2.4e-06,0.43,-2.6e-05,-9.1e-05,-0.00026,0,0,0.095,0.0012,0.00095,0.039,0.066,0.082,0.036,0.056,0.057,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11990000,0.98,-0.0077,-0.012,0.18,0.0067,0.0034,0.014,0.0014,-0.0027,-0.0051,-0.0011,-0.0058,-0.00012,-0.00032,0.00043,-0.14,0.2,-2.7e-06,0.43,-4.4e-05,-9.8e-05,-0.00026,0,0,0.095,0.0011,0.00088,0.039,0.056,0.068,0.032,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -12090000,0.98,-0.0077,-0.012,0.18,0.0098,0.00099,0.017,0.0028,-0.0029,0.00085,-0.001,-0.0058,-0.00012,-0.00051,0.00017,-0.14,0.2,-2.4e-06,0.43,-4.3e-05,-6.6e-05,-0.00025,0,0,0.095,0.0011,0.00088,0.039,0.064,0.079,0.029,0.054,0.056,0.06,9.9e-06,7.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12190000,0.98,-0.0077,-0.012,0.18,0.011,-0.00018,0.016,0.0025,-0.0017,0.0027,-0.001,-0.0058,-0.00012,-0.0012,-0.00048,-0.14,0.2,-2.3e-06,0.43,-7.1e-06,-3.1e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.055,0.065,0.026,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12290000,0.98,-0.0078,-0.012,0.18,0.0081,-0.0037,0.015,0.0032,-0.0024,0.0036,-0.001,-0.0058,-0.00013,-0.0015,-0.0003,-0.14,0.2,-2.1e-06,0.43,2e-05,-3.9e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.062,0.075,0.024,0.053,0.055,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12390000,0.98,-0.0079,-0.012,0.18,0.008,-0.0049,0.013,0.0027,-0.0021,-0.0024,-0.001,-0.0058,-0.00013,-0.0018,-0.00078,-0.14,0.2,-2e-06,0.43,4.7e-05,-1.8e-05,-0.0003,0,0,0.095,0.00084,0.00075,0.039,0.053,0.062,0.022,0.046,0.047,0.056,6.8e-06,5.5e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12490000,0.98,-0.008,-0.012,0.18,0.0096,-0.0064,0.017,0.0041,-0.0032,-0.00046,-0.00099,-0.0058,-0.00013,-0.0021,-0.001,-0.14,0.2,-1.9e-06,0.43,5.5e-05,1.2e-05,-0.00031,0,0,0.095,0.00085,0.00074,0.039,0.06,0.071,0.021,0.053,0.055,0.056,6.7e-06,5.4e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12590000,0.98,-0.008,-0.012,0.18,0.012,-0.01,0.018,0.0043,-0.0042,0.0013,-0.00098,-0.0058,-0.00013,-0.0023,-0.0009,-0.14,0.2,-1.8e-06,0.43,6.9e-05,1.2e-05,-0.00032,0,0,0.095,0.00077,0.00069,0.039,0.051,0.059,0.019,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12690000,0.98,-0.008,-0.012,0.18,0.012,-0.014,0.018,0.0054,-0.0056,0.0028,-0.00097,-0.0058,-0.00013,-0.0024,-0.00085,-0.14,0.2,-1.8e-06,0.43,7.9e-05,1.7e-05,-0.00033,0,0,0.095,0.00077,0.00069,0.039,0.057,0.067,0.018,0.053,0.054,0.054,5.6e-06,4.6e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12790000,0.98,-0.0081,-0.012,0.18,0.014,-0.012,0.019,0.0054,-0.0062,0.005,-0.00098,-0.0058,-0.00013,-0.0018,-0.0013,-0.14,0.2,-1.8e-06,0.43,4.4e-05,4e-05,-0.00031,0,0,0.095,0.0007,0.00065,0.039,0.049,0.056,0.016,0.046,0.047,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12890000,0.98,-0.008,-0.012,0.18,0.016,-0.013,0.021,0.0071,-0.007,0.0079,-0.00099,-0.0058,-0.00012,-0.0014,-0.0015,-0.14,0.2,-1.9e-06,0.43,2.4e-05,4.5e-05,-0.00029,0,0,0.095,0.0007,0.00065,0.039,0.055,0.063,0.016,0.052,0.054,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -12990000,0.98,-0.0079,-0.012,0.18,0.013,-0.0088,0.021,0.005,-0.0047,0.0091,-0.001,-0.0058,-0.00012,-0.0013,-0.0016,-0.14,0.2,-2.4e-06,0.43,3.8e-05,2e-05,-0.00032,0,0,0.095,0.00065,0.00061,0.038,0.047,0.053,0.014,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13090000,0.98,-0.0079,-0.012,0.18,0.015,-0.0077,0.018,0.0067,-0.0048,0.0078,-0.001,-0.0058,-0.00012,-0.00076,-0.0018,-0.14,0.2,-2.4e-06,0.43,1.5e-05,2.5e-05,-0.0003,0,0,0.095,0.00065,0.00061,0.038,0.052,0.059,0.014,0.052,0.054,0.05,4.1e-06,3.4e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13190000,0.98,-0.0079,-0.012,0.18,0.0097,-0.0078,0.017,0.003,-0.0048,0.0084,-0.0011,-0.0058,-0.00012,-0.00054,-0.0023,-0.14,0.2,-2.6e-06,0.43,3.9e-05,2.3e-05,-0.00031,0,0,0.095,0.00061,0.00058,0.038,0.044,0.05,0.013,0.046,0.047,0.048,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13290000,0.98,-0.008,-0.012,0.18,0.011,-0.0095,0.015,0.0046,-0.0059,0.0076,-0.001,-0.0058,-0.00012,-0.00076,-0.0028,-0.14,0.2,-2.4e-06,0.43,4.8e-05,4.4e-05,-0.00031,0,0,0.095,0.00061,0.00058,0.038,0.049,0.056,0.013,0.052,0.054,0.048,3.5e-06,3e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13390000,0.98,-0.0079,-0.012,0.18,0.0091,-0.0081,0.014,0.0032,-0.0049,0.0081,-0.0011,-0.0058,-0.00012,-0.0014,-0.0028,-0.14,0.2,-2.7e-06,0.43,8.6e-05,4.1e-05,-0.00035,0,0,0.095,0.00057,0.00055,0.038,0.042,0.047,0.012,0.045,0.046,0.047,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13490000,0.98,-0.0079,-0.012,0.18,0.011,-0.0068,0.014,0.0048,-0.0056,0.0041,-0.001,-0.0058,-0.00012,-0.0015,-0.0033,-0.14,0.2,-2.6e-06,0.43,8.9e-05,6.4e-05,-0.00035,0,0,0.095,0.00057,0.00055,0.038,0.047,0.052,0.011,0.052,0.053,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13590000,0.98,-0.0079,-0.012,0.18,0.014,-0.0071,0.015,0.0065,-0.0048,0.0025,-0.001,-0.0058,-0.00013,-0.002,-0.0034,-0.14,0.2,-2.6e-06,0.43,9.8e-05,5.7e-05,-0.00035,0,0,0.095,0.00054,0.00053,0.038,0.04,0.044,0.011,0.045,0.046,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13690000,0.98,-0.0078,-0.012,0.18,0.014,-0.0082,0.015,0.0077,-0.0052,0.0051,-0.0011,-0.0058,-0.00012,-0.0017,-0.0031,-0.14,0.2,-2.6e-06,0.43,8.5e-05,3.7e-05,-0.00033,0,0,0.095,0.00054,0.00053,0.038,0.044,0.049,0.011,0.052,0.053,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13790000,0.98,-0.0077,-0.012,0.18,0.019,-0.0044,0.015,0.0098,-0.0027,0.0044,-0.0011,-0.0058,-0.00013,-0.0022,-0.0026,-0.14,0.2,-2.8e-06,0.43,8.3e-05,1.5e-05,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.038,0.042,0.01,0.045,0.046,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13890000,0.98,-0.0076,-0.012,0.18,0.019,-0.0029,0.016,0.011,-0.0025,0.0066,-0.0011,-0.0058,-0.00012,-0.0015,-0.002,-0.14,0.2,-3e-06,0.43,6.2e-05,1.1e-07,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.042,0.046,0.01,0.051,0.053,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13990000,0.98,-0.0076,-0.012,0.18,0.019,-0.001,0.014,0.0088,-0.003,0.0053,-0.0011,-0.0058,-0.00012,-0.001,-0.0025,-0.14,0.2,-2.9e-06,0.43,7e-05,-1.1e-06,-0.00031,0,0,0.095,0.0005,0.0005,0.038,0.036,0.039,0.0097,0.045,0.046,0.043,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -14090000,0.98,-0.0077,-0.011,0.18,0.017,-0.0082,0.015,0.011,-0.0049,0.0015,-0.0011,-0.0058,-0.00013,-0.0028,-0.0023,-0.14,0.2,-2.8e-06,0.43,0.00012,6.9e-06,-0.00035,0,0,0.095,0.0005,0.0005,0.038,0.04,0.043,0.0096,0.051,0.053,0.042,2.2e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14190000,0.98,-0.0078,-0.011,0.18,0.016,-0.0075,0.015,0.01,-0.0045,0.0015,-0.001,-0.0058,-0.00014,-0.0039,-0.0034,-0.14,0.2,-2.6e-06,0.43,0.00018,3.2e-05,-0.00037,0,0,0.095,0.00048,0.00048,0.038,0.034,0.037,0.0094,0.045,0.046,0.042,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14290000,0.98,-0.0077,-0.011,0.18,0.018,-0.0081,0.013,0.012,-0.0054,0.0057,-0.001,-0.0058,-0.00014,-0.004,-0.0036,-0.14,0.2,-2.6e-06,0.43,0.00018,3.6e-05,-0.00036,0,0,0.095,0.00048,0.00048,0.038,0.038,0.041,0.0092,0.051,0.052,0.041,2e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14390000,0.98,-0.0078,-0.011,0.18,0.018,-0.0095,0.015,0.011,-0.0055,0.01,-0.001,-0.0058,-0.00014,-0.0038,-0.0044,-0.14,0.2,-2.4e-06,0.43,0.00019,4.1e-05,-0.00035,0,0,0.095,0.00047,0.00047,0.038,0.033,0.035,0.009,0.045,0.046,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14490000,0.98,-0.008,-0.011,0.18,0.018,-0.011,0.019,0.013,-0.0073,0.012,-0.001,-0.0058,-0.00014,-0.0049,-0.0045,-0.14,0.2,-2.3e-06,0.43,0.00022,5e-05,-0.00037,0,0,0.095,0.00047,0.00047,0.038,0.036,0.038,0.009,0.051,0.052,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14590000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0.0099,-0.0073,0.008,-0.001,-0.0058,-0.00015,-0.0054,-0.0058,-0.14,0.2,-2.1e-06,0.43,0.00027,6.9e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.031,0.033,0.0088,0.045,0.045,0.04,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14690000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0.012,-0.0083,0.0081,-0.001,-0.0058,-0.00014,-0.0053,-0.0062,-0.14,0.2,-2e-06,0.43,0.00027,7.5e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.034,0.036,0.0088,0.05,0.051,0.039,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14790000,0.98,-0.0082,-0.011,0.18,0.019,-0.0034,0.016,0.01,-0.0022,0.011,-0.0011,-0.0058,-0.00014,-0.0047,-0.0076,-0.14,0.2,-2.2e-06,0.43,0.00027,7.3e-05,-0.00035,0,0,0.095,0.00044,0.00045,0.038,0.03,0.031,0.0086,0.044,0.045,0.039,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14890000,0.98,-0.0082,-0.011,0.18,0.021,-0.0055,0.02,0.013,-0.0023,0.012,-0.0011,-0.0058,-0.00013,-0.0042,-0.0093,-0.14,0.2,-1.8e-06,0.43,0.00027,9.5e-05,-0.00031,0,0,0.095,0.00044,0.00045,0.038,0.032,0.034,0.0087,0.05,0.051,0.039,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -14990000,0.98,-0.0083,-0.011,0.18,0.02,-0.0057,0.023,0.012,-0.0029,0.014,-0.0011,-0.0058,-0.00013,-0.0041,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00012,-0.00029,0,0,0.095,0.00043,0.00045,0.038,0.028,0.03,0.0085,0.044,0.045,0.038,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15090000,0.98,-0.0083,-0.011,0.18,0.021,-0.0049,0.026,0.014,-0.0036,0.016,-0.0011,-0.0058,-0.00013,-0.0042,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00013,-0.00029,0,0,0.095,0.00043,0.00045,0.038,0.03,0.032,0.0085,0.05,0.051,0.038,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15190000,0.98,-0.0085,-0.011,0.18,0.019,-0.0059,0.027,0.012,-0.0032,0.017,-0.0011,-0.0058,-0.00014,-0.0048,-0.012,-0.14,0.2,-1.4e-06,0.43,0.00034,0.00014,-0.00029,0,0,0.095,0.00043,0.00044,0.038,0.027,0.028,0.0085,0.044,0.045,0.038,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15290000,0.98,-0.0086,-0.012,0.18,0.022,-0.0065,0.026,0.015,-0.0034,0.014,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.2e-06,0.43,0.00033,0.00017,-0.00027,0,0,0.095,0.00043,0.00044,0.038,0.029,0.031,0.0085,0.049,0.05,0.037,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15390000,0.98,-0.0088,-0.011,0.18,0.021,-0.0039,0.025,0.012,-0.0028,0.014,-0.0011,-0.0058,-0.00013,-0.0045,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,0.095,0.00042,0.00043,0.038,0.025,0.027,0.0084,0.044,0.044,0.037,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15490000,0.98,-0.0088,-0.011,0.18,0.022,-0.0067,0.025,0.014,-0.0034,0.015,-0.0011,-0.0058,-0.00013,-0.0046,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,0.095,0.00042,0.00043,0.038,0.028,0.029,0.0085,0.049,0.05,0.037,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15590000,0.98,-0.0088,-0.011,0.18,0.023,-0.0081,0.025,0.014,-0.0059,0.013,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00036,0.00019,-0.00028,0,0,0.095,0.00041,0.00043,0.038,0.024,0.026,0.0084,0.043,0.044,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15690000,0.98,-0.0086,-0.011,0.18,0.024,-0.01,0.025,0.015,-0.0063,0.014,-0.0011,-0.0058,-0.00012,-0.0032,-0.012,-0.14,0.2,-1.8e-06,0.43,0.00031,0.00013,-0.00026,0,0,0.095,0.00041,0.00043,0.038,0.026,0.028,0.0085,0.049,0.049,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15790000,0.98,-0.0086,-0.011,0.18,0.019,-0.0094,0.025,0.012,-0.0047,0.015,-0.0011,-0.0058,-0.00012,-0.0021,-0.012,-0.14,0.2,-2.2e-06,0.43,0.0003,0.00012,-0.00026,0,0,0.095,0.00041,0.00042,0.038,0.023,0.025,0.0084,0.043,0.044,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15890000,0.98,-0.0087,-0.011,0.18,0.02,-0.0085,0.025,0.015,-0.0061,0.014,-0.0011,-0.0058,-0.00012,-0.0031,-0.012,-0.14,0.2,-1.9e-06,0.43,0.00034,0.00014,-0.00027,0,0,0.095,0.00041,0.00042,0.038,0.025,0.026,0.0085,0.048,0.049,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15990000,0.98,-0.0086,-0.011,0.18,0.018,-0.0074,0.022,0.013,-0.0051,0.013,-0.0011,-0.0058,-0.00012,-0.0034,-0.014,-0.14,0.2,-2.1e-06,0.43,0.00038,0.00019,-0.00029,0,0,0.095,0.0004,0.00042,0.038,0.022,0.023,0.0084,0.043,0.043,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -16090000,0.98,-0.0087,-0.011,0.18,0.019,-0.0092,0.02,0.015,-0.0063,0.013,-0.0011,-0.0058,-0.00013,-0.004,-0.014,-0.14,0.2,-2e-06,0.43,0.00041,0.00021,-0.00031,0,0,0.095,0.0004,0.00042,0.038,0.024,0.025,0.0085,0.048,0.049,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16190000,0.98,-0.0086,-0.011,0.18,0.015,-0.0076,0.018,0.011,-0.0054,0.0094,-0.0011,-0.0058,-0.00013,-0.0047,-0.015,-0.13,0.2,-2e-06,0.43,0.00044,0.00021,-0.00033,0,0,0.095,0.0004,0.00041,0.038,0.021,0.022,0.0084,0.043,0.043,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16290000,0.98,-0.0086,-0.011,0.18,0.017,-0.009,0.018,0.013,-0.0061,0.011,-0.0011,-0.0058,-0.00013,-0.0044,-0.014,-0.13,0.2,-2e-06,0.43,0.00043,0.0002,-0.00032,0,0,0.095,0.0004,0.00041,0.038,0.023,0.024,0.0085,0.047,0.048,0.036,1.2e-06,1e-06,2e-06,0.035,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16390000,0.98,-0.0087,-0.011,0.18,0.019,-0.0081,0.018,0.013,-0.0048,0.011,-0.0011,-0.0058,-0.00013,-0.004,-0.017,-0.13,0.2,-1.7e-06,0.43,0.00045,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.0084,0.042,0.043,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16490000,0.98,-0.0089,-0.011,0.18,0.022,-0.01,0.021,0.015,-0.0059,0.015,-0.0011,-0.0058,-0.00013,-0.0044,-0.017,-0.13,0.2,-1.5e-06,0.43,0.00046,0.00025,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.022,0.023,0.0085,0.047,0.048,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16590000,0.98,-0.0089,-0.011,0.18,0.026,-0.01,0.024,0.013,-0.0049,0.015,-0.0011,-0.0058,-0.00013,-0.0043,-0.018,-0.13,0.2,-1.7e-06,0.43,0.00048,0.00025,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.02,0.021,0.0084,0.042,0.042,0.036,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16690000,0.98,-0.0089,-0.011,0.18,0.028,-0.015,0.024,0.016,-0.0059,0.015,-0.0011,-0.0058,-0.00013,-0.0037,-0.017,-0.13,0.2,-1.9e-06,0.43,0.00046,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.0085,0.047,0.047,0.036,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16790000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.023,0.013,-0.0048,0.015,-0.0011,-0.0058,-0.00012,-0.0031,-0.017,-0.13,0.2,-2.2e-06,0.43,0.00046,0.00024,-0.00029,0,0,0.095,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.042,0.042,0.036,1e-06,9.3e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16890000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.024,0.016,-0.0056,0.013,-0.0011,-0.0058,-0.00012,-0.0021,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00043,0.00023,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.02,0.022,0.0085,0.046,0.047,0.036,1e-06,9.2e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -16990000,0.98,-0.0087,-0.011,0.18,0.026,-0.014,0.024,0.014,-0.0046,0.012,-0.0011,-0.0058,-0.00011,-0.0017,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00044,0.00025,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,1e-06,9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17090000,0.98,-0.0089,-0.011,0.18,0.03,-0.017,0.023,0.018,-0.0063,0.011,-0.0011,-0.0058,-0.00012,-0.0022,-0.019,-0.13,0.2,-2.4e-06,0.43,0.00048,0.00032,-0.00029,0,0,0.095,0.00038,0.0004,0.038,0.02,0.021,0.0085,0.046,0.046,0.035,9.9e-07,8.9e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17190000,0.98,-0.009,-0.011,0.18,0.028,-0.021,0.025,0.014,-0.0096,0.014,-0.0011,-0.0058,-0.00012,-0.0031,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00052,0.00033,-0.00033,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,9.6e-07,8.7e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17290000,0.98,-0.009,-0.011,0.18,0.031,-0.023,0.025,0.017,-0.012,0.014,-0.0011,-0.0058,-0.00013,-0.0038,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00055,0.00034,-0.00035,0,0,0.095,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.045,0.046,0.036,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17390000,0.98,-0.0089,-0.011,0.18,0.025,-0.023,0.024,0.016,-0.009,0.013,-0.0011,-0.0058,-0.00012,-0.0025,-0.018,-0.13,0.2,-3.2e-06,0.43,0.00053,0.00034,-0.00034,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.041,0.041,0.035,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17490000,0.98,-0.009,-0.011,0.18,0.024,-0.025,0.024,0.019,-0.012,0.015,-0.0011,-0.0058,-0.00013,-0.0028,-0.019,-0.13,0.2,-3.2e-06,0.43,0.00054,0.00034,-0.00035,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0085,0.045,0.046,0.036,9.3e-07,8.3e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17590000,0.98,-0.0089,-0.011,0.18,0.021,-0.022,0.023,0.014,-0.0098,0.013,-0.0011,-0.0058,-0.00013,-0.0023,-0.019,-0.13,0.2,-3.8e-06,0.43,0.00055,0.00034,-0.00035,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.04,0.041,0.035,9e-07,8.1e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17690000,0.98,-0.009,-0.011,0.18,0.022,-0.023,0.024,0.016,-0.012,0.015,-0.0011,-0.0058,-0.00013,-0.002,-0.019,-0.13,0.2,-3.5e-06,0.43,0.00053,0.00032,-0.00033,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0084,0.045,0.045,0.035,9e-07,8e-07,2e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17790000,0.98,-0.0091,-0.011,0.18,0.023,-0.022,0.025,0.015,-0.011,0.02,-0.0011,-0.0058,-0.00013,-0.0013,-0.019,-0.13,0.2,-3.5e-06,0.43,0.0005,0.00029,-0.00031,0,0,0.095,0.00037,0.00039,0.038,0.016,0.017,0.0084,0.04,0.041,0.036,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17890000,0.98,-0.0089,-0.011,0.18,0.026,-0.024,0.025,0.017,-0.013,0.025,-0.0011,-0.0058,-0.00012,-0.00072,-0.018,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.0003,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.044,0.045,0.036,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17990000,0.98,-0.0089,-0.011,0.18,0.025,-0.02,0.024,0.016,-0.0083,0.026,-0.0012,-0.0058,-0.00012,9.1e-05,-0.02,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.00029,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0083,0.04,0.04,0.035,8.5e-07,7.6e-07,2e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -18090000,0.98,-0.009,-0.011,0.18,0.026,-0.021,0.024,0.018,-0.01,0.024,-0.0012,-0.0058,-0.00012,0.00014,-0.02,-0.13,0.2,-3.3e-06,0.43,0.00047,0.00027,-0.00028,0,0,0.095,0.00036,0.00038,0.038,0.017,0.018,0.0083,0.044,0.045,0.036,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18190000,0.98,-0.0091,-0.011,0.18,0.025,-0.019,0.024,0.017,-0.0083,0.022,-0.0012,-0.0058,-0.00011,0.0017,-0.021,-0.13,0.2,-3.6e-06,0.43,0.00045,0.00029,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0082,0.04,0.04,0.035,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18290000,0.98,-0.0092,-0.011,0.18,0.028,-0.02,0.023,0.02,-0.01,0.02,-0.0012,-0.0058,-0.00011,0.0019,-0.022,-0.13,0.2,-3.4e-06,0.43,0.00045,0.0003,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.018,0.0082,0.044,0.044,0.036,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18390000,0.98,-0.0091,-0.011,0.18,0.027,-0.019,0.023,0.019,-0.0089,0.019,-0.0012,-0.0058,-0.00011,0.0021,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00046,0.00031,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18490000,0.98,-0.0091,-0.011,0.18,0.031,-0.019,0.022,0.022,-0.01,0.021,-0.0012,-0.0058,-0.00011,0.0027,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00044,0.00031,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0082,0.043,0.044,0.036,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18590000,0.98,-0.0089,-0.011,0.18,0.028,-0.019,0.022,0.019,-0.0093,0.024,-0.0012,-0.0058,-0.00011,0.003,-0.021,-0.13,0.2,-4.2e-06,0.43,0.00044,0.00028,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18690000,0.98,-0.0088,-0.011,0.18,0.028,-0.018,0.021,0.021,-0.011,0.022,-0.0012,-0.0058,-0.00011,0.0039,-0.02,-0.13,0.2,-4.2e-06,0.43,0.0004,0.00025,-0.00022,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0081,0.043,0.044,0.035,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18790000,0.98,-0.0087,-0.011,0.18,0.026,-0.017,0.02,0.019,-0.0093,0.02,-0.0012,-0.0058,-0.00011,0.0044,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00041,0.00026,-0.00023,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.008,0.039,0.04,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18890000,0.98,-0.0087,-0.011,0.18,0.027,-0.018,0.018,0.022,-0.011,0.016,-0.0012,-0.0058,-0.00011,0.0042,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00042,0.00028,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.043,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -18990000,0.98,-0.0087,-0.011,0.18,0.024,-0.018,0.019,0.019,-0.0097,0.02,-0.0012,-0.0058,-0.00011,0.005,-0.019,-0.13,0.2,-5.3e-06,0.43,0.00042,0.00027,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.035,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19090000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.02,0.022,-0.011,0.016,-0.0012,-0.0058,-0.0001,0.0055,-0.019,-0.13,0.2,-5.2e-06,0.43,0.00041,0.00027,-0.00023,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.008,0.042,0.043,0.036,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19190000,0.98,-0.0086,-0.011,0.18,0.02,-0.018,0.02,0.019,-0.01,0.016,-0.0012,-0.0058,-0.00011,0.0053,-0.019,-0.13,0.2,-6e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19290000,0.98,-0.0086,-0.011,0.18,0.021,-0.019,0.02,0.021,-0.012,0.015,-0.0012,-0.0058,-0.00011,0.0053,-0.019,-0.13,0.2,-6e-06,0.43,0.00043,0.00029,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.016,0.022,0.018,-0.0097,0.014,-0.0012,-0.0058,-0.00011,0.0059,-0.019,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,6.9e-07,6.2e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19490000,0.98,-0.0088,-0.011,0.18,0.021,-0.017,0.021,0.021,-0.012,0.014,-0.0012,-0.0058,-0.00012,0.0053,-0.02,-0.13,0.2,-6e-06,0.43,0.00043,0.00026,-0.00025,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,6.9e-07,6.1e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19590000,0.98,-0.0087,-0.011,0.18,0.018,-0.019,0.023,0.019,-0.011,0.014,-0.0012,-0.0058,-0.00012,0.0055,-0.02,-0.13,0.2,-6.3e-06,0.43,0.00043,0.00026,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.015,0.0076,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19690000,0.98,-0.0088,-0.011,0.18,0.018,-0.017,0.022,0.022,-0.013,0.014,-0.0012,-0.0058,-0.00011,0.006,-0.021,-0.13,0.2,-6e-06,0.43,0.00042,0.00026,-0.00024,0,0,0.095,0.00034,0.00036,0.038,0.014,0.016,0.0076,0.042,0.042,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19790000,0.98,-0.0089,-0.011,0.18,0.016,-0.016,0.02,0.021,-0.011,0.01,-0.0012,-0.0058,-0.00012,0.0061,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19890000,0.98,-0.0089,-0.011,0.18,0.017,-0.016,0.021,0.023,-0.013,0.0089,-0.0012,-0.0058,-0.00012,0.006,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19990000,0.98,-0.0089,-0.012,0.18,0.015,-0.016,0.018,0.02,-0.01,0.006,-0.0012,-0.0058,-0.00012,0.007,-0.021,-0.13,0.2,-7e-06,0.43,0.00042,0.00027,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.038,0.038,0.035,6.4e-07,5.7e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.019,0.019,0.022,-0.012,0.0095,-0.0012,-0.0058,-0.00012,0.0071,-0.021,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00028,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.4e-07,5.6e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5.1 -20190000,0.98,-0.0089,-0.012,0.18,0.017,-0.016,0.02,0.022,-0.011,0.0094,-0.0012,-0.0058,-0.00013,0.0071,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00042,0.00029,-0.00027,0,0,0.11,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20290000,0.98,-0.009,-0.012,0.18,0.015,-0.018,0.02,0.023,-0.012,0.01,-0.0012,-0.0058,-0.00012,0.0071,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00042,0.0003,-0.00027,0,0,0.11,0.00034,0.00036,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20390000,0.98,-0.0089,-0.012,0.18,0.013,-0.016,0.02,0.022,-0.011,0.012,-0.0012,-0.0058,-0.00012,0.0081,-0.022,-0.13,0.2,-7.6e-06,0.43,0.00041,0.00028,-0.00026,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20490000,0.98,-0.0089,-0.012,0.18,0.0096,-0.017,0.02,0.023,-0.012,0.0099,-0.0012,-0.0058,-0.00012,0.0082,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00041,0.00027,-0.00026,0,0,0.11,0.00034,0.00035,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20590000,0.98,-0.0088,-0.012,0.18,0.0088,-0.017,0.02,0.022,-0.01,0.0085,-0.0013,-0.0058,-0.00011,0.0094,-0.022,-0.13,0.2,-7.3e-06,0.43,0.00039,0.00025,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20690000,0.98,-0.0087,-0.012,0.18,0.0077,-0.017,0.021,0.022,-0.012,0.0092,-0.0013,-0.0058,-0.00012,0.0092,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00039,0.00025,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.015,0.0072,0.04,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20790000,0.98,-0.0081,-0.012,0.18,0.0038,-0.013,0.0061,0.019,-0.01,0.008,-0.0013,-0.0058,-0.00011,0.01,-0.022,-0.13,0.2,-7.9e-06,0.43,0.00038,0.00025,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20890000,0.98,0.00098,-0.0077,0.18,-4.9e-05,-0.002,-0.11,0.02,-0.011,0.002,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00037,-0.00019,0,0,0.1,0.00033,0.00035,0.038,0.013,0.015,0.0071,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20990000,0.98,0.0044,-0.0043,0.18,-0.012,0.017,-0.25,0.017,-0.0086,-0.013,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00036,-0.00015,0,0,0.087,0.00033,0.00035,0.038,0.013,0.014,0.007,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21090000,0.98,0.0027,-0.0047,0.18,-0.024,0.032,-0.37,0.016,-0.006,-0.043,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-7e-06,0.43,0.00042,0.00016,-0.00019,0,0,0.057,0.00033,0.00035,0.038,0.014,0.015,0.007,0.04,0.041,0.035,5.6e-07,4.9e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21190000,0.98,-6.1e-05,-0.0063,0.18,-0.029,0.039,-0.5,0.013,-0.0039,-0.08,-0.0013,-0.0058,-0.0001,0.01,-0.024,-0.13,0.2,-6.3e-06,0.43,0.00043,0.00019,-0.00018,0,0,0.02,0.00033,0.00034,0.038,0.013,0.014,0.0069,0.037,0.038,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21290000,0.98,-0.0023,-0.0076,0.18,-0.029,0.041,-0.63,0.0099,-0.0003,-0.14,-0.0013,-0.0058,-0.00011,0.0096,-0.024,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00023,-0.00011,0,0,-0.038,0.00033,0.00034,0.037,0.014,0.015,0.0069,0.04,0.041,0.034,5.4e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21390000,0.98,-0.0037,-0.0082,0.18,-0.026,0.038,-0.75,0.0082,0.0037,-0.2,-0.0013,-0.0058,-0.00011,0.0097,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00044,0.00015,-0.00012,0,0,-0.1,0.00032,0.00034,0.037,0.013,0.014,0.0068,0.037,0.038,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21490000,0.98,-0.0045,-0.0086,0.18,-0.021,0.035,-0.89,0.0054,0.0077,-0.29,-0.0013,-0.0058,-0.0001,0.01,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00018,-0.00017,0,0,-0.19,0.00032,0.00034,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21590000,0.98,-0.0049,-0.0086,0.18,-0.015,0.032,-1,0.0044,0.0099,-0.38,-0.0013,-0.0058,-9.5e-05,0.011,-0.024,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00023,-0.00018,0,0,-0.28,0.00032,0.00034,0.037,0.013,0.015,0.0067,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21690000,0.98,-0.0052,-0.0085,0.18,-0.012,0.027,-1.1,0.0032,0.013,-0.49,-0.0013,-0.0058,-8.8e-05,0.011,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00027,-0.00016,0,0,-0.39,0.00032,0.00034,0.037,0.014,0.016,0.0067,0.04,0.041,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21790000,0.98,-0.0055,-0.0086,0.18,-0.0065,0.022,-1.3,0.007,0.012,-0.61,-0.0013,-0.0058,-7.8e-05,0.012,-0.023,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00027,-0.00022,0,0,-0.51,0.00032,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21890000,0.98,-0.0058,-0.0088,0.18,-0.0029,0.017,-1.4,0.0062,0.014,-0.75,-0.0013,-0.0058,-8.1e-05,0.012,-0.023,-0.13,0.2,-6.8e-06,0.43,0.00036,0.00029,-0.00021,0,0,-0.65,0.00032,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21990000,0.98,-0.0064,-0.009,0.18,-0.00083,0.013,-1.4,0.01,0.011,-0.89,-0.0013,-0.0058,-7.5e-05,0.012,-0.022,-0.13,0.2,-6.5e-06,0.43,0.00039,0.0003,-0.00023,0,0,-0.79,0.00031,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22090000,0.98,-0.0071,-0.0099,0.18,0.0012,0.0095,-1.4,0.0095,0.013,-1,-0.0013,-0.0058,-6.6e-05,0.012,-0.022,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00031,-0.00024,0,0,-0.93,0.00031,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22190000,0.98,-0.0075,-0.01,0.18,0.007,0.0051,-1.4,0.015,0.008,-1.2,-0.0013,-0.0058,-5.8e-05,0.013,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00039,0.00033,-0.00024,0,0,-1.1,0.00031,0.00032,0.037,0.013,0.014,0.0065,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22290000,0.98,-0.0082,-0.01,0.18,0.013,-0.00054,-1.4,0.016,0.0081,-1.3,-0.0013,-0.0058,-6e-05,0.013,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00039,0.00033,-0.00023,0,0,-1.2,0.00031,0.00032,0.037,0.014,0.015,0.0065,0.04,0.041,0.034,4.8e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22390000,0.98,-0.0085,-0.01,0.18,0.017,-0.0091,-1.4,0.022,-0.00072,-1.5,-0.0013,-0.0058,-6.3e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00033,-0.00026,0,0,-1.4,0.0003,0.00032,0.037,0.013,0.014,0.0064,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22490000,0.98,-0.0087,-0.011,0.18,0.021,-0.016,-1.4,0.024,-0.0023,-1.6,-0.0013,-0.0058,-6.7e-05,0.011,-0.02,-0.13,0.2,-6.9e-06,0.43,0.00041,0.00035,-0.00028,0,0,-1.5,0.00031,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.7e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22590000,0.98,-0.0086,-0.012,0.18,0.029,-0.024,-1.4,0.034,-0.01,-1.7,-0.0013,-0.0058,-5.8e-05,0.012,-0.02,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00037,-0.00027,0,0,-1.6,0.0003,0.00032,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.028,-1.4,0.038,-0.013,-1.9,-0.0013,-0.0058,-6.1e-05,0.012,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00041,0.00037,-0.00028,0,0,-1.8,0.0003,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.036,-1.4,0.048,-0.022,-2,-0.0013,-0.0058,-6.4e-05,0.011,-0.021,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00034,-0.00031,0,0,-1.9,0.0003,0.00031,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22890000,0.98,-0.0087,-0.012,0.18,0.042,-0.041,-1.4,0.052,-0.026,-2.2,-0.0013,-0.0058,-5.6e-05,0.011,-0.021,-0.13,0.2,-6.3e-06,0.43,0.00041,0.00035,-0.00029,0,0,-2.1,0.0003,0.00031,0.037,0.013,0.015,0.0063,0.04,0.041,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.045,-1.4,0.061,-0.035,-2.3,-0.0013,-0.0058,-4.7e-05,0.012,-0.02,-0.13,0.2,-6.7e-06,0.43,0.0004,0.00032,-0.00026,0,0,-2.2,0.0003,0.00031,0.037,0.012,0.014,0.0062,0.036,0.038,0.033,4.3e-07,3.9e-07,1.6e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23090000,0.98,-0.0086,-0.013,0.18,0.051,-0.05,-1.4,0.065,-0.04,-2.5,-0.0013,-0.0058,-4.6e-05,0.012,-0.02,-0.13,0.2,-6.7e-06,0.43,0.00039,0.00033,-0.00025,0,0,-2.4,0.0003,0.00031,0.037,0.013,0.014,0.0062,0.04,0.041,0.033,4.3e-07,3.9e-07,1.5e-06,0.028,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23190000,0.98,-0.0086,-0.013,0.18,0.057,-0.052,-1.4,0.076,-0.05,-2.6,-0.0013,-0.0058,-4.9e-05,0.012,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00037,0.0003,-0.00025,0,0,-2.5,0.00029,0.00031,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23290000,0.98,-0.0091,-0.014,0.18,0.062,-0.057,-1.4,0.082,-0.055,-2.8,-0.0013,-0.0058,-4.6e-05,0.012,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00034,0.00034,-0.00025,0,0,-2.7,0.00029,0.00031,0.037,0.013,0.014,0.0062,0.039,0.041,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23390000,0.98,-0.009,-0.014,0.18,0.067,-0.06,-1.4,0.092,-0.061,-2.9,-0.0013,-0.0058,-5.9e-05,0.012,-0.019,-0.13,0.2,-7.7e-06,0.43,0.00035,0.00031,-0.00023,0,0,-2.8,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23490000,0.98,-0.0091,-0.014,0.18,0.072,-0.062,-1.4,0.1,-0.067,-3,-0.0013,-0.0058,-5.1e-05,0.012,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00033,0.00037,-0.00028,0,0,-2.9,0.00029,0.0003,0.037,0.013,0.014,0.0061,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23590000,0.98,-0.0093,-0.014,0.18,0.075,-0.064,-1.4,0.11,-0.076,-3.2,-0.0013,-0.0058,-4.8e-05,0.013,-0.019,-0.13,0.2,-8.4e-06,0.43,0.00029,0.00033,-0.00024,0,0,-3.1,0.00029,0.0003,0.037,0.012,0.013,0.006,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23690000,0.98,-0.01,-0.015,0.18,0.074,-0.066,-1.3,0.11,-0.082,-3.3,-0.0013,-0.0058,-4e-05,0.013,-0.02,-0.13,0.2,-8.3e-06,0.43,0.00027,0.00036,-0.00024,0,0,-3.2,0.00029,0.0003,0.037,0.012,0.014,0.006,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23790000,0.98,-0.012,-0.017,0.18,0.068,-0.062,-0.95,0.12,-0.086,-3.4,-0.0013,-0.0058,-3.8e-05,0.014,-0.02,-0.13,0.2,-8e-06,0.43,0.00025,0.00039,-0.00022,0,0,-3.3,0.00029,0.0003,0.037,0.011,0.013,0.006,0.036,0.037,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23890000,0.98,-0.015,-0.021,0.18,0.064,-0.062,-0.52,0.13,-0.092,-3.5,-0.0013,-0.0058,-3.6e-05,0.014,-0.02,-0.13,0.2,-8e-06,0.43,0.00024,0.00041,-0.00024,0,0,-3.4,0.00029,0.0003,0.037,0.012,0.013,0.006,0.039,0.041,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23990000,0.98,-0.017,-0.024,0.18,0.064,-0.061,-0.13,0.14,-0.095,-3.6,-0.0013,-0.0058,-4.2e-05,0.015,-0.019,-0.13,0.2,-8.1e-06,0.43,0.0002,0.00043,3.8e-06,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.033,3.9e-07,3.5e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24090000,0.98,-0.017,-0.023,0.18,0.07,-0.069,0.099,0.14,-0.1,-3.6,-0.0013,-0.0058,-4.5e-05,0.015,-0.019,-0.13,0.2,-8.1e-06,0.43,0.00022,0.0004,3.7e-06,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24190000,0.98,-0.014,-0.019,0.18,0.08,-0.074,0.089,0.15,-0.1,-3.6,-0.0013,-0.0058,-4.5e-05,0.017,-0.019,-0.13,0.2,-7.7e-06,0.43,0.00022,0.00037,0.0001,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.032,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24290000,0.98,-0.012,-0.016,0.18,0.084,-0.078,0.067,0.16,-0.11,-3.6,-0.0013,-0.0058,-4.3e-05,0.017,-0.019,-0.13,0.2,-7.3e-06,0.43,0.00025,0.00032,9.8e-05,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24390000,0.98,-0.011,-0.015,0.18,0.077,-0.073,0.083,0.16,-0.11,-3.6,-0.0013,-0.0058,-4.2e-05,0.018,-0.02,-0.13,0.2,-6e-06,0.43,0.00024,0.00036,0.00016,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24490000,0.98,-0.011,-0.015,0.18,0.073,-0.069,0.081,0.17,-0.12,-3.6,-0.0013,-0.0058,-2.8e-05,0.019,-0.021,-0.13,0.2,-6e-06,0.43,0.00017,0.00047,0.00021,0,0,-3.5,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24590000,0.98,-0.012,-0.015,0.18,0.069,-0.066,0.077,0.17,-0.12,-3.6,-0.0013,-0.0058,-3.9e-05,0.02,-0.021,-0.13,0.2,-4.7e-06,0.43,0.0002,0.00044,0.00023,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24690000,0.98,-0.012,-0.015,0.18,0.068,-0.065,0.076,0.18,-0.12,-3.5,-0.0013,-0.0058,-3.8e-05,0.02,-0.021,-0.13,0.2,-4.9e-06,0.43,0.00019,0.00047,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24790000,0.98,-0.012,-0.014,0.18,0.065,-0.063,0.068,0.18,-0.12,-3.5,-0.0014,-0.0058,-4.6e-05,0.022,-0.022,-0.13,0.2,-4.3e-06,0.43,0.00019,0.00047,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24890000,0.98,-0.012,-0.014,0.18,0.063,-0.067,0.057,0.19,-0.13,-3.5,-0.0014,-0.0058,-4e-05,0.022,-0.022,-0.13,0.2,-4.1e-06,0.43,0.00018,0.00048,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24990000,0.98,-0.012,-0.014,0.18,0.055,-0.063,0.05,0.19,-0.12,-3.5,-0.0014,-0.0058,-5.4e-05,0.024,-0.023,-0.13,0.2,-4.3e-06,0.43,0.00015,0.00059,0.00025,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25090000,0.98,-0.012,-0.014,0.18,0.051,-0.063,0.048,0.19,-0.12,-3.5,-0.0014,-0.0058,-5.4e-05,0.024,-0.023,-0.13,0.2,-4.9e-06,0.43,0.00013,0.00066,0.00029,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25190000,0.98,-0.012,-0.014,0.18,0.046,-0.057,0.048,0.19,-0.12,-3.5,-0.0014,-0.0058,-7.2e-05,0.025,-0.024,-0.13,0.2,-4.9e-06,0.43,0.00011,0.00069,0.00028,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25290000,0.98,-0.012,-0.013,0.18,0.041,-0.059,0.043,0.2,-0.12,-3.5,-0.0014,-0.0058,-7.9e-05,0.025,-0.023,-0.13,0.2,-5.5e-06,0.43,0.0001,0.00072,0.00025,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25390000,0.98,-0.012,-0.013,0.18,0.033,-0.052,0.041,0.19,-0.11,-3.5,-0.0014,-0.0058,-9.4e-05,0.027,-0.024,-0.13,0.2,-6.3e-06,0.43,6.6e-05,0.00077,0.00026,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25490000,0.98,-0.013,-0.013,0.18,0.028,-0.052,0.041,0.19,-0.12,-3.5,-0.0014,-0.0058,-9.6e-05,0.027,-0.025,-0.13,0.2,-6.1e-06,0.43,6e-05,0.00073,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25590000,0.98,-0.013,-0.012,0.18,0.023,-0.049,0.042,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-6.9e-06,0.43,2.9e-05,0.00076,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25690000,0.98,-0.012,-0.012,0.18,0.023,-0.048,0.031,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-7e-06,0.43,3.4e-05,0.00078,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25790000,0.98,-0.012,-0.012,0.18,0.012,-0.04,0.031,0.18,-0.1,-3.5,-0.0014,-0.0058,-0.00012,0.029,-0.026,-0.13,0.2,-7.5e-06,0.43,-2.6e-05,0.00071,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25890000,0.98,-0.012,-0.012,0.18,0.006,-0.039,0.033,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.00013,0.029,-0.026,-0.13,0.2,-7.6e-06,0.43,-4.6e-05,0.00068,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25990000,0.98,-0.012,-0.012,0.18,-0.003,-0.032,0.027,0.17,-0.097,-3.5,-0.0014,-0.0058,-0.00015,0.031,-0.026,-0.13,0.2,-9e-06,0.43,-0.0001,0.00066,0.00014,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26090000,0.98,-0.012,-0.012,0.18,-0.0076,-0.032,0.026,0.17,-0.1,-3.5,-0.0014,-0.0058,-0.00014,0.031,-0.026,-0.13,0.2,-8.5e-06,0.43,-9.8e-05,0.00065,0.00017,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26190000,0.98,-0.012,-0.012,0.18,-0.015,-0.025,0.021,0.16,-0.092,-3.5,-0.0015,-0.0058,-0.00014,0.032,-0.026,-0.13,0.2,-8.9e-06,0.43,-0.00012,0.00065,0.00019,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26290000,0.98,-0.012,-0.013,0.18,-0.015,-0.024,0.015,0.16,-0.095,-3.5,-0.0015,-0.0058,-0.00015,0.032,-0.027,-0.13,0.2,-9.5e-06,0.43,-0.00013,0.00066,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26390000,0.98,-0.011,-0.013,0.18,-0.021,-0.017,0.019,0.15,-0.086,-3.5,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00017,0.00064,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26490000,0.98,-0.011,-0.013,0.18,-0.023,-0.015,0.028,0.14,-0.087,-3.5,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00017,0.00067,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26590000,0.98,-0.01,-0.013,0.18,-0.026,-0.0064,0.029,0.13,-0.079,-3.5,-0.0015,-0.0058,-0.00017,0.034,-0.028,-0.13,0.2,-1.2e-05,0.43,-0.0002,0.00069,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26690000,0.98,-0.01,-0.012,0.18,-0.027,-0.0024,0.027,0.13,-0.08,-3.5,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00021,0.0007,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.0019,0.027,0.12,-0.073,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00024,0.00068,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26890000,0.98,-0.0092,-0.012,0.18,-0.04,0.0048,0.022,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00024,0.00066,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.012,0.022,0.098,-0.065,-3.5,-0.0015,-0.0058,-0.00019,0.035,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00026,0.00065,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27090000,0.98,-0.0085,-0.013,0.18,-0.05,0.018,0.025,0.093,-0.064,-3.5,-0.0015,-0.0058,-0.00019,0.035,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00064,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27190000,0.98,-0.0086,-0.013,0.18,-0.056,0.025,0.027,0.081,-0.056,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00027,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27290000,0.98,-0.0088,-0.014,0.18,-0.063,0.03,0.14,0.076,-0.054,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00027,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0054,0.038,0.039,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27390000,0.98,-0.01,-0.016,0.18,-0.071,0.037,0.46,0.064,-0.045,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.5e-05,0.43,-0.00033,0.00056,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27490000,0.98,-0.012,-0.018,0.18,-0.074,0.042,0.78,0.057,-0.041,-3.5,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.00031,0.00052,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27590000,0.98,-0.011,-0.017,0.18,-0.07,0.046,0.87,0.046,-0.036,-3.4,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00029,0.00047,0.00021,0,0,-3.3,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27690000,0.98,-0.01,-0.014,0.18,-0.065,0.042,0.78,0.04,-0.031,-3.3,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00046,0.00019,0,0,-3.2,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27790000,0.98,-0.0088,-0.012,0.18,-0.065,0.04,0.77,0.032,-0.027,-3.2,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00042,0.0002,0,0,-3.1,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27890000,0.98,-0.0085,-0.013,0.18,-0.071,0.047,0.81,0.026,-0.023,-3.2,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00042,0.0002,0,0,-3.1,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27990000,0.98,-0.0089,-0.013,0.18,-0.072,0.049,0.8,0.019,-0.019,-3.1,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00027,0.00036,0.00022,0,0,-3,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28090000,0.98,-0.0092,-0.013,0.18,-0.076,0.05,0.8,0.011,-0.014,-3,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00038,0.00021,0,0,-2.9,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28190000,0.98,-0.0086,-0.013,0.18,-0.077,0.047,0.81,0.004,-0.012,-2.9,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00037,0.00022,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28290000,0.98,-0.0081,-0.013,0.18,-0.081,0.051,0.81,-0.0032,-0.0067,-2.9,-0.0015,-0.0058,-0.00018,0.034,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00039,0.00019,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.055,0.81,-0.0097,-0.0023,-2.8,-0.0014,-0.0058,-0.00017,0.033,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00032,0.0003,0.0002,0,0,-2.7,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28490000,0.98,-0.0084,-0.015,0.18,-0.085,0.058,0.81,-0.019,0.0032,-2.7,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00029,0.00029,0.00023,0,0,-2.6,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28590000,0.98,-0.0085,-0.014,0.18,-0.079,0.054,0.81,-0.023,0.0026,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00027,0.00022,0,0,-2.5,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28690000,0.98,-0.0082,-0.014,0.18,-0.078,0.055,0.81,-0.031,0.008,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00023,0.00027,0.00022,0,0,-2.5,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28790000,0.98,-0.0076,-0.014,0.18,-0.076,0.056,0.81,-0.035,0.011,-2.5,-0.0014,-0.0058,-0.00015,0.032,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.00017,0.00022,0,0,-2.4,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28890000,0.98,-0.0074,-0.013,0.18,-0.08,0.058,0.81,-0.043,0.017,-2.4,-0.0014,-0.0058,-0.00014,0.032,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00025,0.0002,0.00019,0,0,-2.3,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28990000,0.98,-0.0072,-0.013,0.18,-0.077,0.055,0.81,-0.044,0.017,-2.3,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00029,5.9e-05,0.00023,0,0,-2.2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29090000,0.98,-0.007,-0.013,0.18,-0.08,0.057,0.81,-0.052,0.023,-2.3,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00031,4.1e-05,0.00023,0,0,-2.2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29190000,0.98,-0.0069,-0.014,0.18,-0.078,0.056,0.81,-0.052,0.023,-2.2,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00033,-8.9e-05,0.00024,0,0,-2.1,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29290000,0.98,-0.0072,-0.014,0.18,-0.081,0.062,0.81,-0.061,0.029,-2.1,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00033,-0.00011,0.00024,0,0,-2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29390000,0.98,-0.0076,-0.013,0.18,-0.078,0.061,0.81,-0.06,0.031,-2,-0.0014,-0.0058,-0.00011,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00036,-0.00024,0.00025,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.8e-07,2.6e-07,9.9e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29490000,0.98,-0.0076,-0.013,0.18,-0.081,0.062,0.81,-0.069,0.038,-2,-0.0014,-0.0058,-0.0001,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00039,-0.00021,0.00023,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29590000,0.98,-0.0075,-0.013,0.18,-0.077,0.061,0.81,-0.067,0.038,-1.9,-0.0014,-0.0058,-8.7e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00043,-0.00031,0.00023,0,0,-1.8,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29690000,0.98,-0.0075,-0.013,0.18,-0.082,0.06,0.81,-0.076,0.044,-1.8,-0.0014,-0.0058,-8e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00045,-0.00028,0.00021,0,0,-1.7,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29790000,0.98,-0.0073,-0.013,0.18,-0.079,0.054,0.81,-0.072,0.043,-1.7,-0.0014,-0.0058,-6.4e-05,0.027,-0.028,-0.12,0.2,-2.5e-05,0.43,-0.00051,-0.0004,0.00021,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29890000,0.98,-0.0068,-0.013,0.18,-0.08,0.056,0.8,-0.08,0.048,-1.7,-0.0014,-0.0058,-5.7e-05,0.028,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.00053,-0.00037,0.00019,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29990000,0.98,-0.007,-0.013,0.18,-0.075,0.051,0.8,-0.076,0.044,-1.6,-0.0014,-0.0058,-4.6e-05,0.027,-0.029,-0.12,0.2,-2.6e-05,0.43,-0.00051,-0.00042,0.00021,0,0,-1.5,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.5e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30090000,0.98,-0.0071,-0.013,0.18,-0.077,0.051,0.8,-0.084,0.049,-1.5,-0.0014,-0.0058,-5.6e-05,0.026,-0.028,-0.12,0.2,-2.7e-05,0.43,-0.00046,-0.00048,0.00026,0,0,-1.4,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.4e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30190000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,-0.078,0.047,-1.5,-0.0014,-0.0058,-5.9e-05,0.026,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00047,-0.0007,0.00032,0,0,-1.4,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30290000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,-0.085,0.052,-1.4,-0.0014,-0.0058,-5.7e-05,0.026,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00051,-0.00075,0.00032,0,0,-1.3,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30390000,0.98,-0.0071,-0.013,0.18,-0.065,0.043,0.8,-0.078,0.049,-1.3,-0.0014,-0.0058,-4e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00065,-0.00096,0.00032,0,0,-1.2,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30490000,0.98,-0.0071,-0.013,0.18,-0.069,0.043,0.8,-0.085,0.054,-1.2,-0.0014,-0.0058,-3.4e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00069,-0.00095,0.0003,0,0,-1.1,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.2e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30590000,0.98,-0.0074,-0.014,0.18,-0.064,0.041,0.8,-0.077,0.051,-1.2,-0.0014,-0.0058,-1.8e-05,0.025,-0.03,-0.12,0.2,-3e-05,0.43,-0.00079,-0.0011,0.0003,0,0,-1.1,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.1e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30690000,0.98,-0.0078,-0.014,0.18,-0.063,0.04,0.8,-0.084,0.055,-1.1,-0.0014,-0.0058,-1.8e-05,0.025,-0.03,-0.12,0.2,-3e-05,0.43,-0.00077,-0.001,0.00029,0,0,-0.99,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.5e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30790000,0.98,-0.0075,-0.013,0.17,-0.056,0.034,0.8,-0.076,0.053,-1,-0.0014,-0.0058,-1.4e-05,0.024,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00085,-0.0012,0.00033,0,0,-0.92,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30890000,0.98,-0.0069,-0.013,0.17,-0.056,0.031,0.79,-0.081,0.056,-0.95,-0.0014,-0.0058,-2.1e-05,0.024,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00075,-0.0011,0.00035,0,0,-0.85,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30990000,0.98,-0.0071,-0.013,0.17,-0.049,0.025,0.8,-0.071,0.049,-0.88,-0.0014,-0.0057,-1.3e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00079,-0.0013,0.00038,0,0,-0.78,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31090000,0.98,-0.0073,-0.013,0.17,-0.048,0.024,0.79,-0.075,0.052,-0.81,-0.0014,-0.0057,-1.8e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00074,-0.0012,0.00039,0,0,-0.71,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31190000,0.98,-0.0075,-0.013,0.17,-0.043,0.02,0.8,-0.066,0.047,-0.74,-0.0013,-0.0057,-1.7e-06,0.024,-0.033,-0.12,0.2,-3.4e-05,0.43,-0.00084,-0.0012,0.00038,0,0,-0.64,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31290000,0.98,-0.0077,-0.014,0.17,-0.04,0.018,0.8,-0.07,0.049,-0.67,-0.0013,-0.0057,3.4e-06,0.024,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00087,-0.0012,0.00037,0,0,-0.57,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31390000,0.98,-0.0075,-0.013,0.17,-0.035,0.011,0.8,-0.061,0.043,-0.59,-0.0013,-0.0057,2.7e-06,0.023,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00096,-0.0015,0.00042,0,0,-0.49,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31490000,0.98,-0.0073,-0.014,0.17,-0.036,0.0081,0.8,-0.065,0.044,-0.52,-0.0013,-0.0057,1e-06,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.001,-0.0017,0.00043,0,0,-0.42,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.5e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31590000,0.98,-0.0071,-0.014,0.17,-0.033,0.0062,0.8,-0.054,0.04,-0.45,-0.0013,-0.0057,1.1e-05,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.0011,-0.0018,0.00045,0,0,-0.35,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.5e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31690000,0.98,-0.0071,-0.014,0.17,-0.036,0.0056,0.8,-0.058,0.041,-0.38,-0.0013,-0.0057,1.9e-05,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.0012,-0.0018,0.00043,0,0,-0.28,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31790000,0.98,-0.0074,-0.015,0.17,-0.027,0.003,0.8,-0.045,0.039,-0.3,-0.0013,-0.0057,2.4e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0019,0.00045,0,0,-0.2,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31890000,0.99,-0.0071,-0.015,0.17,-0.025,0.00083,0.8,-0.049,0.039,-0.23,-0.0013,-0.0057,2.8e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.002,0.00047,0,0,-0.13,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31990000,0.99,-0.0074,-0.014,0.17,-0.017,-0.00026,0.79,-0.036,0.036,-0.17,-0.0013,-0.0057,2.5e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0022,0.00052,0,0,-0.066,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32090000,0.99,-0.0077,-0.014,0.17,-0.019,-0.0037,0.8,-0.038,0.036,-0.094,-0.0013,-0.0057,2.5e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0023,0.00054,0,0,0.0058,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32190000,0.99,-0.008,-0.014,0.17,-0.013,-0.0073,0.8,-0.026,0.034,-0.026,-0.0013,-0.0057,2.1e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0024,0.00058,0,0,0.074,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32290000,0.99,-0.0079,-0.015,0.17,-0.013,-0.0098,0.8,-0.027,0.033,0.044,-0.0013,-0.0057,2.6e-05,0.025,-0.034,-0.12,0.2,-2.8e-05,0.43,-0.0015,-0.0025,0.00059,0,0,0.14,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32390000,0.99,-0.008,-0.015,0.17,-0.0063,-0.011,0.8,-0.015,0.03,0.12,-0.0013,-0.0057,2.3e-05,0.025,-0.034,-0.12,0.2,-2.6e-05,0.43,-0.0016,-0.0027,0.00065,0,0,0.22,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32490000,0.99,-0.011,-0.012,0.17,0.018,-0.077,-0.076,-0.014,0.024,0.12,-0.0013,-0.0057,1.9e-05,0.025,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0015,-0.0027,0.00064,0,0,0.22,0.00028,0.00028,0.035,0.012,0.014,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32590000,0.99,-0.011,-0.013,0.17,0.021,-0.079,-0.079,0.0015,0.02,0.1,-0.0013,-0.0057,1.8e-05,0.025,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,0.2,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32690000,0.99,-0.011,-0.012,0.17,0.016,-0.085,-0.08,0.0033,0.012,0.09,-0.0013,-0.0057,1.7e-05,0.025,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,0.19,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32790000,0.99,-0.011,-0.013,0.17,0.017,-0.084,-0.081,0.015,0.0093,0.074,-0.0013,-0.0057,1.6e-05,0.025,-0.034,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0022,0.00078,0,0,0.17,0.00028,0.00027,0.035,0.011,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32890000,0.99,-0.011,-0.013,0.17,0.017,-0.09,-0.083,0.017,0.00078,0.059,-0.0013,-0.0057,1.9e-05,0.025,-0.034,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0021,0.00079,0,0,0.16,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32990000,0.98,-0.011,-0.013,0.17,0.017,-0.089,-0.082,0.028,-0.0031,0.046,-0.0014,-0.0057,2.1e-05,0.025,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00085,0,0,0.15,0.00027,0.00027,0.035,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -33090000,0.98,-0.011,-0.013,0.17,0.013,-0.093,-0.079,0.029,-0.012,0.038,-0.0014,-0.0057,2.1e-05,0.025,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00085,0,0,0.14,0.00027,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -33190000,0.98,-0.01,-0.013,0.17,0.011,-0.094,-0.078,0.037,-0.015,0.031,-0.0014,-0.0057,1.2e-05,0.026,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0015,-0.002,0.00088,0,0,0.13,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 -33290000,0.98,-0.01,-0.013,0.17,0.0073,-0.096,-0.078,0.037,-0.024,0.023,-0.0014,-0.0057,2.3e-05,0.026,-0.034,-0.12,0.2,-2.1e-05,0.43,-0.0016,-0.0021,0.00092,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 -33390000,0.98,-0.01,-0.013,0.17,0.0052,-0.09,-0.076,0.043,-0.022,0.014,-0.0014,-0.0057,1.6e-05,0.028,-0.033,-0.12,0.2,-1.8e-05,0.43,-0.0016,-0.002,0.00096,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.033 -33490000,0.98,-0.01,-0.013,0.17,-0.00014,-0.093,-0.075,0.042,-0.031,0.0042,-0.0014,-0.0057,2.1e-05,0.028,-0.032,-0.12,0.2,-1.7e-05,0.43,-0.0017,-0.0021,0.00098,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.058 -33590000,0.98,-0.01,-0.013,0.17,-0.0029,-0.092,-0.072,0.046,-0.029,-0.0037,-0.0014,-0.0057,2e-05,0.029,-0.031,-0.12,0.2,-1.3e-05,0.43,-0.0018,-0.0022,0.001,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.083 -33690000,0.98,-0.01,-0.013,0.17,-0.0062,-0.095,-0.073,0.046,-0.038,-0.012,-0.0014,-0.0057,2.4e-05,0.029,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.0018,-0.002,0.001,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.11 -33790000,0.98,-0.01,-0.013,0.17,-0.0081,-0.092,-0.068,0.052,-0.036,-0.019,-0.0014,-0.0057,1.4e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0017,-0.0019,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.13 -33890000,0.98,-0.01,-0.013,0.17,-0.012,-0.093,-0.067,0.051,-0.045,-0.025,-0.0014,-0.0057,2.4e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0018,-0.0018,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.16 -33990000,0.98,-0.0099,-0.013,0.17,-0.013,-0.088,-0.064,0.055,-0.04,-0.029,-0.0014,-0.0057,1.1e-05,0.033,-0.031,-0.12,0.2,-8.6e-06,0.43,-0.0017,-0.0018,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.18 -34090000,0.98,-0.0098,-0.013,0.17,-0.017,-0.093,-0.062,0.054,-0.049,-0.033,-0.0014,-0.0057,1.4e-05,0.033,-0.031,-0.12,0.2,-9e-06,0.43,-0.0017,-0.0017,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.21 -34190000,0.98,-0.0098,-0.013,0.17,-0.018,-0.088,-0.06,0.058,-0.044,-0.037,-0.0014,-0.0057,1e-05,0.035,-0.031,-0.12,0.2,-6.6e-06,0.43,-0.0017,-0.0016,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.23 -34290000,0.98,-0.0096,-0.013,0.17,-0.019,-0.092,-0.058,0.056,-0.052,-0.043,-0.0014,-0.0057,1.7e-05,0.035,-0.031,-0.12,0.2,-5.9e-06,0.43,-0.0017,-0.0016,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.26 -34390000,0.98,-0.0095,-0.013,0.17,-0.021,-0.085,-0.054,0.058,-0.047,-0.047,-0.0014,-0.0056,9.7e-06,0.036,-0.03,-0.12,0.2,-3.8e-06,0.43,-0.0016,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.28 -34490000,0.98,-0.0095,-0.013,0.17,-0.024,-0.089,-0.052,0.057,-0.055,-0.05,-0.0014,-0.0056,1.8e-05,0.036,-0.03,-0.12,0.2,-3.5e-06,0.43,-0.0017,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.31 -34590000,0.98,-0.0094,-0.013,0.17,-0.026,-0.081,0.74,0.059,-0.05,-0.021,-0.0014,-0.0056,1.1e-05,0.038,-0.03,-0.12,0.2,-1e-06,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 -34690000,0.98,-0.0094,-0.013,0.17,-0.03,-0.079,1.7,0.056,-0.058,0.098,-0.0014,-0.0056,1.4e-05,0.038,-0.03,-0.12,0.2,-7.2e-07,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.36 -34790000,0.98,-0.0093,-0.013,0.17,-0.033,-0.07,2.7,0.058,-0.052,0.28,-0.0015,-0.0056,7.7e-06,0.04,-0.031,-0.12,0.2,1.9e-06,0.43,-0.0017,-0.0013,0.0013,0,0,0.12,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 -34890000,0.98,-0.0092,-0.013,0.17,-0.038,-0.069,3.7,0.055,-0.058,0.57,-0.0015,-0.0056,1.1e-05,0.04,-0.031,-0.12,0.2,2e-06,0.43,-0.0017,-0.0013,0.0013,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 +10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,0,0,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,8.1e-05,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.032 +90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,0,0,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.1,0.01,0.01,0.00036,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.058 +190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.035,0,0,-4.9e+02,1.6e-09,-1.4e-09,-6.4e-11,0,0,-3.2e-06,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00084,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.082 +290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.038,0,0,-4.9e+02,7.3e-09,-1.1e-08,-3.9e-10,0,0,-2e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.012,0.012,0.00075,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.11 +390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.05,0,0,-4.9e+02,-2.1e-10,-1.4e-08,-3.2e-10,0,0,-1.4e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0049,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.13 +490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.055,0,0,-4.9e+02,-1.2e-06,7.3e-07,4.1e-08,0,0,-1.9e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.013,0.013,0.00072,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.16 +590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.1,0,0,-4.9e+02,-1.3e-06,7.6e-07,4.5e-08,0,0,6.3e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.015,0.015,0.00099,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.18 +690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.039,0,0,-4.9e+02,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00017,0,0,0,0,0,0,0,0,-4.9e+02,0.016,0.016,0.00061,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.21 +790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.045,0,0,-4.9e+02,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,-4.9e+02,0.018,0.018,0.00077,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.00098,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.23 +890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.086,0,0,-4.9e+02,-2.2e-05,1e-06,4.9e-07,0,0,-7.4e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.019,0.019,0.00051,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.26 +990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.11,0,0,-4.9e+02,-2.2e-05,9.9e-07,4.9e-07,0,0,-9.4e-06,0,0,0,0,0,0,0,0,-4.9e+02,0.021,0.021,0.00062,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00053,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.28 +1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0,0,-4.9e+02,-6.1e-05,-1.5e-05,9.8e-07,0,0,3.8e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.023,0.023,0.00043,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.31 +1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.1,0,0,-4.9e+02,-5.8e-05,-1.4e-05,9.7e-07,0,0,-0.00052,0,0,0,0,0,0,0,0,-4.9e+02,0.025,0.025,0.00051,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 +1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.1,0,0,-4.9e+02,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00079,0,0,0,0,0,0,0,0,-4.9e+02,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 +1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.094,0,0,-4.9e+02,-0.00016,-9.3e-05,1.5e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,-4.9e+02,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 +1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.11,0,0,-4.9e+02,-0.00039,-0.00033,1.2e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,-4.9e+02,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1590000,1,-0.012,-0.014,0.0004,0.031,-0.024,-0.13,0,0,-4.9e+02,-0.00039,-0.00033,1.2e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,-4.9e+02,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.012,-0.014,0.00045,0.028,-0.019,-0.13,0,0,-4.9e+02,-0.00073,-0.00074,-3.4e-07,0,0,-0.0018,0,0,0,0,0,0,0,0,-4.9e+02,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0,0,-4.9e+02,-0.00073,-0.00073,-2.9e-07,0,0,-0.0028,0,0,0,0,0,0,0,0,-4.9e+02,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0,0,-4.9e+02,-0.00072,-0.00072,-2.7e-07,0,0,-0.0032,0,0,0,0,0,0,0,0,-4.9e+02,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,0.00041,0.035,-0.018,-0.14,0,0,-4.9e+02,-0.0011,-0.0013,-3.6e-06,0,0,-0.0046,0,0,0,0,0,0,0,0,-4.9e+02,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0,0,-4.9e+02,-0.0011,-0.0012,-3.5e-06,0,0,-0.0064,0,0,0,0,0,0,0,0,-4.9e+02,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,0.00039,0.033,-0.014,-0.14,0,0,-4.9e+02,-0.0014,-0.0018,-8.7e-06,0,0,-0.0075,0,0,0,0,0,0,0,0,-4.9e+02,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,0.00039,0.038,-0.014,-0.14,0,0,-4.9e+02,-0.0014,-0.0018,-8.5e-06,0,0,-0.0097,0,0,0,0,0,0,0,0,-4.9e+02,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,0.0004,0.029,-0.01,-0.14,0,0,-4.9e+02,-0.0017,-0.0023,-1.4e-05,0,0,-0.012,0,0,0,0,0,0,0,0,-4.9e+02,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.014,0.00048,0.033,-0.0091,-0.14,0,0,-4.9e+02,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0,0,0,0,0,0,0,0,-4.9e+02,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.01,-0.013,0.0004,0.023,-0.0062,-0.15,0,0,-4.9e+02,-0.0018,-0.0027,-2e-05,0,0,-0.015,0,0,0,0,0,0,0,0,-4.9e+02,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.01,-0.013,0.00044,0.027,-0.0055,-0.15,0,0,-4.9e+02,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,-4.9e+02,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.01,-0.013,0.00038,0.022,-0.0032,-0.14,0,0,-4.9e+02,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.01,-0.013,0.00031,0.026,-0.005,-0.14,0,0,-4.9e+02,-0.0019,-0.003,-2.5e-05,0,0,-0.025,0,0,0,0,0,0,0,0,-4.9e+02,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.01,-0.013,0.00033,0.02,-0.0039,-0.15,0,0,-4.9e+02,-0.002,-0.0033,-3e-05,0,0,-0.028,0,0,0,0,0,0,0,0,-4.9e+02,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.01,-0.013,0.00053,0.025,-0.0068,-0.15,0,0,-4.9e+02,-0.002,-0.0033,-3e-05,0,0,-0.031,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.01,-0.013,0.00058,0.02,-0.0065,-0.15,0,0,-4.9e+02,-0.0021,-0.0036,-3.5e-05,0,0,-0.032,0,0,0,0,0,0,0,0,-4.9e+02,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.01,-0.013,0.0006,0.023,-0.0067,-0.15,0,0,-4.9e+02,-0.0021,-0.0036,-3.4e-05,0,0,-0.034,0,0,0,0,0,0,0,0,-4.9e+02,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.0098,-0.013,0.00061,0.019,-0.0036,-0.15,0,0,-4.9e+02,-0.0021,-0.0038,-3.8e-05,0,0,-0.039,0,0,0,0,0,0,0,0,-4.9e+02,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.0097,-0.013,0.0006,0.025,-0.0023,-0.15,0,0,-4.9e+02,-0.0021,-0.0038,-3.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,-4.9e+02,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.0095,-0.012,0.00056,0.021,-0.0018,-0.15,0,0,-4.9e+02,-0.0022,-0.004,-4.2e-05,0,0,-0.046,0,0,0,0,0,0,0,0,-4.9e+02,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.0095,-0.013,0.00054,0.024,-0.0011,-0.15,0,0,-4.9e+02,-0.0022,-0.004,-4.2e-05,0,0,-0.051,0,0,0,0,0,0,0,0,-4.9e+02,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.0094,-0.012,0.00057,0.019,0.0033,-0.15,0,0,-4.9e+02,-0.0022,-0.0043,-4.7e-05,0,0,-0.054,0,0,0,0,0,0,0,0,-4.9e+02,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.0094,-0.013,0.00065,0.021,0.0045,-0.14,0,0,-4.9e+02,-0.0022,-0.0042,-4.7e-05,0,0,-0.058,0,0,0,0,0,0,0,0,-4.9e+02,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.0094,-0.013,0.00072,0.026,0.0042,-0.14,0,0,-4.9e+02,-0.0022,-0.0042,-4.7e-05,0,0,-0.063,0,0,0,0,0,0,0,0,-4.9e+02,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.0093,-0.012,0.00078,0.022,0.0037,-0.12,0,0,-4.9e+02,-0.0022,-0.0044,-5.1e-05,0,0,-0.071,0,0,0,0,0,0,0,0,-4.9e+02,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.0094,-0.012,0.00075,0.024,0.0034,-0.12,0,0,-4.9e+02,-0.0022,-0.0044,-5.1e-05,0,0,-0.074,0,0,0,0,0,0,0,0,-4.9e+02,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.0095,-0.012,0.00076,0.021,0.0033,-0.13,0,0,-4.9e+02,-0.0022,-0.0046,-5.6e-05,0,0,-0.076,0,0,0,0,0,0,0,0,-4.9e+02,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.0094,-0.012,0.00072,0.025,0.0018,-0.11,0,0,-4.9e+02,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,-4.9e+02,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.0094,-0.012,0.00078,0.021,0.0036,-0.11,0,0,-4.9e+02,-0.0022,-0.0048,-6.1e-05,0,0,-0.086,0,0,0,0,0,0,0,0,-4.9e+02,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.0094,-0.012,0.00085,0.023,0.0024,-0.11,0,0,-4.9e+02,-0.0022,-0.0048,-6.1e-05,0,0,-0.088,0,0,0,0,0,0,0,0,-4.9e+02,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.0094,-0.012,0.00079,0.017,0.0027,-0.1,0,0,-4.9e+02,-0.0021,-0.005,-6.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,-4.9e+02,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.0093,-0.012,0.00089,0.015,0.0048,-0.1,0,0,-4.9e+02,-0.0021,-0.005,-6.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,-4.9e+02,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.0093,-0.012,0.00093,0.01,0.0024,-0.093,0,0,-4.9e+02,-0.0021,-0.0051,-6.9e-05,0,0,-0.099,0,0,0,0,0,0,0,0,-4.9e+02,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.0092,-0.012,0.00091,0.013,0.0031,-0.085,0,0,-4.9e+02,-0.0021,-0.0051,-6.9e-05,0,0,-0.1,0,0,0,0,0,0,0,0,-4.9e+02,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.0091,-0.011,0.00099,0.01,0.0034,-0.083,0,0,-4.9e+02,-0.0021,-0.0052,-7.2e-05,0,0,-0.1,0,0,0,0,0,0,0,0,-4.9e+02,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.0089,-0.012,0.001,0.0099,0.007,-0.08,0,0,-4.9e+02,-0.0021,-0.0052,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0071,-0.069,0,0,-4.9e+02,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0,0,-4.9e+02,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.061,0,0,-4.9e+02,-0.002,-0.0054,-7.7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.054,0,0,-4.9e+02,-0.002,-0.0054,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0089,-0.011,0.00093,0.0077,0.016,-0.053,0,0,-4.9e+02,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0088,-0.011,0.00088,0.0089,0.018,-0.05,0,0,-4.9e+02,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0088,-0.011,0.00092,0.0095,0.015,-0.048,0,0,-4.9e+02,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0088,-0.012,0.00089,0.011,0.017,-0.042,0,0,-4.9e+02,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0088,-0.011,0.00071,0.011,0.018,-0.039,0,0,-4.9e+02,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0089,-0.011,0.00072,0.0087,0.017,-0.038,0,0,-4.9e+02,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0089,-0.011,0.00075,0.008,0.019,-0.041,0,0,-4.9e+02,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0089,-0.011,0.00076,0.0082,0.016,-0.042,0,0,-4.9e+02,-0.0018,-0.0056,-8.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0089,-0.011,0.00066,0.0057,0.016,-0.04,0,0,-4.9e+02,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0089,-0.011,0.00059,0.0039,0.015,-0.042,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0088,-0.011,0.00055,0.0022,0.018,-0.044,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6790000,1,-0.0089,-0.011,0.00052,0.0029,0.015,-0.043,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6890000,1,-0.0087,-0.011,0.00043,0.0023,0.015,-0.039,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +6990000,0.98,-0.0067,-0.012,0.18,0.0025,0.011,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,-4.9e+02,0.0012,0.0012,0.054,0.16,0.17,0.031,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 +7090000,0.98,-0.0065,-0.012,0.18,0.00012,0.018,-0.038,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,-4.9e+02,0.0013,0.0013,0.048,0.18,0.19,0.03,0.13,0.13,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7190000,0.98,-0.0065,-0.012,0.18,-6.1e-05,0.019,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.7e-06,0,0,-4.9e+02,0.0013,0.0013,0.046,0.21,0.21,0.029,0.16,0.16,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7290000,0.98,-0.0064,-0.012,0.18,-0.00068,0.024,-0.034,0,0,-4.9e+02,-0.0016,-0.0057,-9.2e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,-4.9e+02,0.0014,0.0013,0.044,0.24,0.24,0.028,0.19,0.19,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7390000,0.98,-0.0063,-0.012,0.18,-0.0015,0.00094,-0.032,0,0,-4.9e+02,-0.0017,-0.0057,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-5.7e-05,0.43,-0.00048,-0.0004,8.8e-05,0,0,-4.9e+02,0.0014,0.0014,0.043,25,25,0.027,1e+02,1e+02,0.064,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00027,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7490000,0.98,-0.0063,-0.012,0.18,0.00097,0.0035,-0.026,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-4.5e-05,0.43,-0.00042,-0.00038,-7.9e-05,0,0,-4.9e+02,0.0015,0.0014,0.043,25,25,0.026,1e+02,1e+02,0.063,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00022,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7590000,0.98,-0.0064,-0.012,0.18,0.0021,0.006,-0.023,0,0,-4.9e+02,-0.0017,-0.0056,-9e-05,-0.00036,0.00036,-0.13,0.2,-3.8e-05,0.43,-0.00034,-0.00039,-9.5e-06,0,0,-4.9e+02,0.0015,0.0015,0.042,25,25,0.025,51,51,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00019,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7690000,0.98,-0.0064,-0.013,0.18,0.0021,0.0093,-0.022,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-3.4e-05,0.43,-0.00031,-0.0004,2.4e-06,0,0,-4.9e+02,0.0016,0.0015,0.042,25,25,0.025,52,52,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00017,0.0013,0.0014,0.0016,0.0013,1,1,2 +7790000,0.98,-0.0064,-0.013,0.18,0.0056,0.01,-0.025,0,0,-4.9e+02,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.9e-05,0.43,-0.00021,-0.00039,-1.5e-06,0,0,-4.9e+02,0.0016,0.0016,0.042,24,24,0.024,35,35,0.061,6.3e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00015,0.0013,0.0014,0.0016,0.0013,1,1,2 +7890000,0.98,-0.0065,-0.013,0.18,0.0046,0.014,-0.025,0,0,-4.9e+02,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.6e-05,0.43,-0.00019,-0.0004,4.4e-05,0,0,-4.9e+02,0.0016,0.0016,0.042,24,24,0.023,36,36,0.06,6.3e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00013,0.0013,0.0014,0.0016,0.0013,1,1,2 +7990000,0.98,-0.0063,-0.013,0.18,0.0032,0.017,-0.022,0,0,-4.9e+02,-0.0016,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-2.5e-05,0.43,-0.0002,-0.00042,7.4e-05,0,0,-4.9e+02,0.0017,0.0016,0.042,24,24,0.022,28,28,0.059,6.2e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00012,0.0013,0.0014,0.0016,0.0013,1,1,2 +8090000,0.98,-0.0063,-0.013,0.18,0.0043,0.019,-0.022,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,-0.00036,0.00036,-0.13,0.2,-2.2e-05,0.43,-0.00017,-0.00042,9.9e-05,0,0,-4.9e+02,0.0017,0.0017,0.042,24,24,0.022,30,30,0.059,6.2e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,0.00011,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8190000,0.98,-0.0064,-0.012,0.18,0.0052,0.022,-0.018,0,0,-4.9e+02,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.44,-0.00014,-0.00041,0.00014,0,0,-4.9e+02,0.0018,0.0017,0.041,23,23,0.021,24,24,0.058,6.1e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,0.0001,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8290000,0.98,-0.0062,-0.012,0.18,0.002,0.028,-0.017,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.43,-0.00014,-0.00044,6.7e-05,0,0,-4.9e+02,0.0018,0.0017,0.041,23,23,0.02,27,27,0.057,6.1e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,9.6e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8390000,0.98,-0.0062,-0.012,0.18,-0.0023,0.028,-0.016,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00044,2.1e-05,0,0,-4.9e+02,0.0019,0.0018,0.041,21,21,0.02,23,23,0.057,6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8490000,0.98,-0.0059,-0.012,0.18,-0.0061,0.035,-0.017,0,0,-4.9e+02,-0.0017,-0.0059,-9.6e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00048,-7.4e-06,0,0,-4.9e+02,0.0019,0.0018,0.041,21,21,0.019,25,25,0.056,5.9e-05,5.6e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8590000,0.98,-0.006,-0.012,0.18,-0.00035,0.034,-0.012,0,0,-4.9e+02,-0.0016,-0.0057,-9.6e-05,-0.00036,0.00036,-0.14,0.2,-1.7e-05,0.43,-0.00018,-0.00043,3.3e-06,0,0,-4.9e+02,0.0019,0.0018,0.041,19,19,0.018,22,22,0.055,5.8e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,7.9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8690000,0.98,-0.006,-0.012,0.18,-0.0022,0.037,-0.014,0,0,-4.9e+02,-0.0016,-0.0058,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-1.6e-05,0.43,-0.00022,-0.00045,-8.7e-05,0,0,-4.9e+02,0.002,0.0018,0.041,19,19,0.018,24,24,0.055,5.8e-05,5.3e-05,2.2e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8790000,0.98,-0.006,-0.012,0.18,-0.005,0.039,-0.014,0,0,-4.9e+02,-0.0016,-0.0058,-9.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00019,-0.00045,-0.00013,0,0,-4.9e+02,0.002,0.0018,0.041,19,19,0.018,27,27,0.055,5.7e-05,5.2e-05,2.2e-06,0.04,0.04,0.00099,0.0013,7.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8890000,0.98,-0.006,-0.012,0.18,0.00053,0.041,-0.0094,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00026,-0.00043,-0.00011,0,0,-4.9e+02,0.002,0.0018,0.041,17,17,0.017,24,24,0.054,5.6e-05,5e-05,2.2e-06,0.04,0.04,0.00094,0.0013,6.7e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +8990000,0.98,-0.0059,-0.013,0.18,0.01,0.047,-0.0086,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00037,-0.00039,-6.6e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,17,17,0.017,27,27,0.054,5.5e-05,4.9e-05,2.2e-06,0.04,0.04,0.00091,0.0013,6.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +9090000,0.98,-0.0055,-0.012,0.18,-0.00033,0.056,-0.0096,0,0,-4.9e+02,-0.0018,-0.0057,-8.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00028,-0.00049,-8.8e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,15,15,0.016,24,24,0.053,5.3e-05,4.7e-05,2.2e-06,0.04,0.04,0.00087,0.0013,6.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +9190000,0.98,-0.0053,-0.013,0.18,0.0029,0.064,-0.009,0,0,-4.9e+02,-0.0018,-0.0057,-8.6e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00031,-0.00053,-0.00011,0,0,-4.9e+02,0.0021,0.0018,0.041,15,15,0.016,27,27,0.052,5.2e-05,4.5e-05,2.2e-06,0.04,0.04,0.00083,0.0013,5.9e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.3 +9290000,0.98,-0.0053,-0.013,0.18,0.013,0.062,-0.0074,0,0,-4.9e+02,-0.0018,-0.0056,-8.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.0004,-0.00049,-8.5e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,13,13,0.015,24,24,0.052,5.1e-05,4.4e-05,2.2e-06,0.04,0.04,0.00079,0.0013,5.6e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 +9390000,0.98,-0.0054,-0.013,0.18,0.014,0.06,-0.0063,0,0,-4.9e+02,-0.0017,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00035,-0.00043,-3.8e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,13,13,0.015,26,26,0.052,5e-05,4.2e-05,2.2e-06,0.04,0.04,0.00077,0.0013,5.4e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 +9490000,0.98,-0.0053,-0.013,0.18,0.0087,0.061,-0.0046,0,0,-4.9e+02,-0.0018,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00033,-0.00048,-7.6e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,12,12,0.015,23,23,0.051,4.8e-05,4e-05,2.2e-06,0.04,0.04,0.00074,0.0013,5.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 +9590000,0.98,-0.0057,-0.013,0.18,0.0078,0.052,-0.0045,0,0,-4.9e+02,-0.0016,-0.0057,-9.3e-05,-0.00036,0.00036,-0.14,0.2,-1e-05,0.43,-0.00031,-0.00041,-0.00012,0,0,-4.9e+02,0.0022,0.0018,0.041,12,12,0.014,26,26,0.05,4.7e-05,3.9e-05,2.2e-06,0.04,0.04,0.00071,0.0013,5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 +9690000,0.98,-0.0059,-0.013,0.18,0.0096,0.047,-0.0016,0,0,-4.9e+02,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-9.2e-06,0.43,-0.00031,-0.00038,-9.9e-05,0,0,-4.9e+02,0.0022,0.0018,0.041,10,10,0.014,23,23,0.05,4.6e-05,3.7e-05,2.2e-06,0.04,0.04,0.00068,0.0013,4.8e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9790000,0.98,-0.0061,-0.012,0.18,0.001,0.041,-0.003,0,0,-4.9e+02,-0.0015,-0.0058,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.7e-06,0.43,-0.00019,-0.00036,-0.00015,0,0,-4.9e+02,0.0022,0.0017,0.041,10,10,0.014,25,25,0.05,4.4e-05,3.5e-05,2.2e-06,0.04,0.04,0.00066,0.0013,4.7e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9890000,0.98,-0.0061,-0.012,0.18,0.0086,0.04,-0.0017,0,0,-4.9e+02,-0.0015,-0.0057,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.6e-06,0.43,-0.00023,-0.00034,-9.4e-05,0,0,-4.9e+02,0.0022,0.0017,0.041,8.6,8.7,0.013,22,22,0.049,4.3e-05,3.4e-05,2.2e-06,0.04,0.04,0.00063,0.0013,4.5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9990000,0.98,-0.0063,-0.012,0.18,0.0025,0.034,-0.001,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-6.4e-06,0.43,-0.00014,-0.00033,-0.00013,0,0,-4.9e+02,0.0022,0.0017,0.041,8.6,8.7,0.013,24,24,0.049,4.2e-05,3.2e-05,2.2e-06,0.04,0.04,0.00061,0.0013,4.4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +10090000,0.98,-0.0067,-0.012,0.18,0.00072,0.019,0.00016,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-4.9e-06,0.43,-9.8e-05,-0.00025,-0.00015,0,0,-4.9e+02,0.0022,0.0017,0.041,7.4,7.5,0.013,21,21,0.048,4e-05,3.1e-05,2.2e-06,0.04,0.04,0.00059,0.0013,4.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10190000,0.98,-0.0072,-0.012,0.18,0.0053,0.0047,0.001,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00036,0.00036,-0.14,0.2,-3.3e-06,0.43,-9.1e-05,-0.00012,-0.00015,0,0,-4.9e+02,0.0022,0.0016,0.041,7.4,7.6,0.012,23,23,0.048,3.9e-05,2.9e-05,2.2e-06,0.04,0.04,0.00057,0.0013,4.1e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10290000,0.98,-0.0071,-0.012,0.18,0.012,0.0085,-3.9e-05,0,0,-4.9e+02,-0.0012,-0.0057,-0.00011,-0.00036,0.00036,-0.14,0.2,-3.7e-06,0.43,-0.00016,-0.00011,-0.00012,0,0,-4.9e+02,0.0022,0.0016,0.041,6.4,6.5,0.012,20,20,0.048,3.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10390000,0.98,-0.0071,-0.012,0.18,0.0076,0.0026,-0.0025,0,0,-4.9e+02,-0.0012,-0.0056,-0.00011,-0.0003,0.00041,-0.14,0.2,-3.9e-06,0.43,-0.0002,-0.00011,-6.5e-05,0,0,-4.9e+02,0.0022,0.0016,0.041,0.25,0.25,0.56,0.5,0.5,0.048,3.6e-05,2.7e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10490000,0.98,-0.0073,-0.012,0.18,0.0096,0.00082,0.007,0,0,-4.9e+02,-0.0011,-0.0057,-0.00011,-0.00033,0.00027,-0.14,0.2,-3e-06,0.43,-0.00016,-5.9e-05,-8.7e-05,0,0,-4.9e+02,0.0021,0.0016,0.041,0.25,0.26,0.55,0.51,0.51,0.057,3.5e-05,2.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10590000,0.98,-0.007,-0.012,0.18,0.00031,-0.00018,0.013,0,0,-4.9e+02,-0.0012,-0.0056,-0.00011,-0.0003,0.00025,-0.14,0.2,-3.6e-06,0.43,-0.00018,-9.8e-05,-7.3e-05,0,0,-4.9e+02,0.0021,0.0015,0.041,0.13,0.13,0.27,0.17,0.17,0.055,3.3e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10690000,0.98,-0.0071,-0.013,0.18,0.0031,-0.0028,0.016,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.00027,0.00018,-0.14,0.2,-3.3e-06,0.43,-0.00021,-4.9e-05,-7e-05,0,0,-4.9e+02,0.0021,0.0015,0.041,0.13,0.14,0.26,0.17,0.18,0.065,3.2e-05,2.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10790000,0.98,-0.0073,-0.013,0.18,0.0057,-0.006,0.014,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.00016,7.3e-05,-0.14,0.2,-3.1e-06,0.43,-0.00026,1.3e-05,-9e-05,0,0,-4.9e+02,0.002,0.0014,0.041,0.09,0.095,0.17,0.11,0.11,0.061,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10890000,0.98,-0.0069,-0.013,0.18,0.008,-0.0029,0.01,0,0,-4.9e+02,-0.0012,-0.0055,-0.00011,-5.4e-05,0.0002,-0.14,0.2,-4.1e-06,0.43,-0.00033,-3e-05,-7.2e-05,0,0,-4.9e+02,0.002,0.0014,0.041,0.097,0.1,0.16,0.11,0.11,0.068,2.9e-05,2e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +10990000,0.98,-0.0069,-0.013,0.18,0.0054,0.0032,0.016,0,0,-4.9e+02,-0.0012,-0.0056,-0.00011,-0.00021,0.00015,-0.14,0.2,-4.1e-06,0.43,-0.00026,-5.9e-05,-0.00012,0,0,-4.9e+02,0.0019,0.0014,0.041,0.074,0.081,0.12,0.079,0.079,0.065,2.6e-05,1.9e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11090000,0.98,-0.0075,-0.013,0.18,0.0093,0.0017,0.02,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.0003,-5.8e-05,-0.14,0.2,-2.9e-06,0.43,-0.00024,2.5e-05,-0.0001,0,0,-4.9e+02,0.0019,0.0013,0.041,0.082,0.093,0.11,0.084,0.085,0.069,2.6e-05,1.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11190000,0.98,-0.0077,-0.013,0.18,0.0083,0.0023,0.026,0,0,-4.9e+02,-0.001,-0.0056,-0.00012,-0.00041,-1.3e-05,-0.14,0.2,-2.4e-06,0.43,-0.00017,-1.2e-06,-0.00012,0,0,-4.9e+02,0.0017,0.0013,0.04,0.066,0.076,0.084,0.065,0.066,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11290000,0.98,-0.0077,-0.012,0.18,0.0065,-0.0003,0.025,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00052,0.00011,-0.14,0.2,-2.2e-06,0.43,-0.0001,-4e-05,-0.00015,0,0,-4.9e+02,0.0017,0.0012,0.04,0.074,0.088,0.078,0.071,0.072,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11390000,0.98,-0.0076,-0.012,0.18,0.0045,0.00081,0.016,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00054,1.8e-05,-0.14,0.2,-2.3e-06,0.43,-7.8e-05,-5.1e-05,-0.00018,0,0,-4.9e+02,0.0015,0.0012,0.04,0.062,0.074,0.064,0.058,0.058,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11490000,0.98,-0.0075,-0.012,0.18,0.0052,-0.00071,0.02,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00052,-6.5e-05,-0.14,0.2,-2.3e-06,0.43,-9.9e-05,-3e-05,-0.00017,0,0,-4.9e+02,0.0015,0.0011,0.04,0.071,0.086,0.058,0.063,0.064,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11590000,0.98,-0.0076,-0.012,0.18,0.0047,-0.00064,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00061,2.5e-05,-0.14,0.2,-2.3e-06,0.43,-5e-05,-6.9e-05,-0.00019,0,0,-4.9e+02,0.0014,0.0011,0.04,0.06,0.072,0.049,0.053,0.054,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11690000,0.98,-0.0075,-0.012,0.18,0.0042,0.0018,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00057,0.00015,-0.14,0.2,-2.5e-06,0.43,-4.4e-05,-8.6e-05,-0.00022,0,0,-4.9e+02,0.0014,0.001,0.04,0.068,0.084,0.046,0.059,0.06,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11790000,0.98,-0.0075,-0.012,0.18,0.0028,0.0026,0.019,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-4.6e-05,0.00011,-0.14,0.2,-2.6e-06,0.43,-5.7e-05,-9.1e-05,-0.00022,0,0,-4.9e+02,0.0012,0.00096,0.039,0.058,0.07,0.039,0.05,0.051,0.062,1.3e-05,9.4e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11890000,0.98,-0.0077,-0.012,0.18,0.0039,0.0012,0.017,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00025,0.00027,-0.14,0.2,-2.4e-06,0.43,-2.6e-05,-9.1e-05,-0.00026,0,0,-4.9e+02,0.0012,0.00096,0.039,0.066,0.082,0.036,0.056,0.058,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11990000,0.98,-0.0077,-0.012,0.18,0.0067,0.0034,0.014,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00032,0.00042,-0.14,0.2,-2.7e-06,0.43,-4.4e-05,-9.8e-05,-0.00026,0,0,-4.9e+02,0.0011,0.00088,0.039,0.057,0.068,0.032,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +12090000,0.98,-0.0077,-0.012,0.18,0.0099,0.001,0.017,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00051,0.00017,-0.14,0.2,-2.4e-06,0.43,-4.3e-05,-6.6e-05,-0.00025,0,0,-4.9e+02,0.0011,0.00088,0.039,0.064,0.079,0.029,0.055,0.056,0.06,1e-05,7.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12190000,0.98,-0.0077,-0.012,0.18,0.011,-0.00015,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0012,-0.00048,-0.14,0.2,-2.3e-06,0.43,-6.9e-06,-3e-05,-0.00028,0,0,-4.9e+02,0.00094,0.00081,0.039,0.055,0.065,0.026,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12290000,0.98,-0.0078,-0.012,0.18,0.0081,-0.0036,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0015,-0.00031,-0.14,0.2,-2.1e-06,0.43,2e-05,-3.8e-05,-0.00028,0,0,-4.9e+02,0.00095,0.00081,0.039,0.062,0.075,0.024,0.054,0.056,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12390000,0.98,-0.0079,-0.012,0.18,0.008,-0.0049,0.013,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0018,-0.00078,-0.14,0.2,-2e-06,0.43,4.7e-05,-1.7e-05,-0.0003,0,0,-4.9e+02,0.00085,0.00075,0.039,0.053,0.062,0.022,0.047,0.048,0.056,6.9e-06,5.6e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12490000,0.98,-0.008,-0.012,0.18,0.0096,-0.0064,0.017,0,0,-4.9e+02,-0.00099,-0.0058,-0.00013,-0.0021,-0.001,-0.14,0.2,-1.9e-06,0.43,5.5e-05,1.3e-05,-0.00031,0,0,-4.9e+02,0.00085,0.00075,0.039,0.06,0.071,0.021,0.053,0.055,0.056,6.8e-06,5.4e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12590000,0.98,-0.0081,-0.012,0.18,0.012,-0.01,0.018,0,0,-4.9e+02,-0.00098,-0.0058,-0.00013,-0.0022,-0.0009,-0.14,0.2,-1.8e-06,0.43,6.9e-05,1.3e-05,-0.00032,0,0,-4.9e+02,0.00077,0.0007,0.039,0.051,0.059,0.019,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12690000,0.98,-0.008,-0.012,0.18,0.012,-0.014,0.018,0,0,-4.9e+02,-0.00097,-0.0058,-0.00013,-0.0024,-0.00085,-0.14,0.2,-1.8e-06,0.43,7.9e-05,1.7e-05,-0.00033,0,0,-4.9e+02,0.00077,0.00069,0.039,0.057,0.067,0.018,0.053,0.055,0.054,5.7e-06,4.6e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12790000,0.98,-0.0081,-0.012,0.18,0.014,-0.012,0.02,0,0,-4.9e+02,-0.00098,-0.0058,-0.00013,-0.0017,-0.0013,-0.14,0.2,-1.8e-06,0.43,4.4e-05,4.1e-05,-0.00031,0,0,-4.9e+02,0.0007,0.00065,0.039,0.049,0.056,0.016,0.046,0.047,0.052,4.8e-06,4.1e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12890000,0.98,-0.008,-0.012,0.18,0.016,-0.013,0.021,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.0014,-0.0015,-0.14,0.2,-1.9e-06,0.43,2.4e-05,4.5e-05,-0.00029,0,0,-4.9e+02,0.00071,0.00065,0.039,0.055,0.063,0.016,0.052,0.054,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +12990000,0.98,-0.0079,-0.012,0.18,0.013,-0.0088,0.021,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0013,-0.0016,-0.14,0.2,-2.4e-06,0.43,3.8e-05,2e-05,-0.00032,0,0,-4.9e+02,0.00065,0.00061,0.038,0.047,0.053,0.014,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13090000,0.98,-0.0079,-0.012,0.18,0.015,-0.0077,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00075,-0.0018,-0.14,0.2,-2.4e-06,0.43,1.5e-05,2.6e-05,-0.0003,0,0,-4.9e+02,0.00065,0.00061,0.038,0.052,0.059,0.014,0.052,0.054,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13190000,0.98,-0.0079,-0.012,0.18,0.0097,-0.0078,0.017,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00053,-0.0023,-0.14,0.2,-2.6e-06,0.43,3.9e-05,2.4e-05,-0.00031,0,0,-4.9e+02,0.00061,0.00058,0.038,0.044,0.05,0.013,0.046,0.047,0.048,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13290000,0.98,-0.008,-0.012,0.18,0.011,-0.0095,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00076,-0.0028,-0.14,0.2,-2.4e-06,0.43,4.8e-05,4.4e-05,-0.00031,0,0,-4.9e+02,0.00061,0.00058,0.038,0.049,0.056,0.013,0.052,0.054,0.048,3.6e-06,3e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13390000,0.98,-0.0079,-0.012,0.18,0.0091,-0.0081,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0014,-0.0028,-0.14,0.2,-2.7e-06,0.43,8.6e-05,4.2e-05,-0.00035,0,0,-4.9e+02,0.00057,0.00056,0.038,0.042,0.047,0.012,0.045,0.046,0.047,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13490000,0.98,-0.0079,-0.012,0.18,0.011,-0.0068,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0015,-0.0033,-0.14,0.2,-2.6e-06,0.43,8.9e-05,6.4e-05,-0.00035,0,0,-4.9e+02,0.00058,0.00056,0.038,0.047,0.052,0.011,0.052,0.053,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13590000,0.98,-0.0079,-0.012,0.18,0.014,-0.0071,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.002,-0.0034,-0.14,0.2,-2.6e-06,0.43,9.8e-05,5.7e-05,-0.00035,0,0,-4.9e+02,0.00054,0.00053,0.038,0.04,0.044,0.011,0.045,0.046,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13690000,0.98,-0.0078,-0.012,0.18,0.014,-0.0082,0.015,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0016,-0.0031,-0.14,0.2,-2.6e-06,0.43,8.5e-05,3.7e-05,-0.00033,0,0,-4.9e+02,0.00055,0.00053,0.038,0.044,0.049,0.011,0.052,0.053,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13790000,0.98,-0.0077,-0.012,0.18,0.019,-0.0044,0.015,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0022,-0.0026,-0.14,0.2,-2.8e-06,0.43,8.3e-05,1.6e-05,-0.00034,0,0,-4.9e+02,0.00052,0.00051,0.038,0.038,0.042,0.01,0.045,0.046,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13890000,0.98,-0.0076,-0.012,0.18,0.019,-0.0029,0.016,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0015,-0.002,-0.14,0.2,-3e-06,0.43,6.2e-05,3.3e-07,-0.00034,0,0,-4.9e+02,0.00052,0.00052,0.038,0.042,0.046,0.01,0.051,0.053,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13990000,0.98,-0.0076,-0.012,0.18,0.019,-0.001,0.014,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.001,-0.0025,-0.14,0.2,-2.9e-06,0.43,7e-05,-9.3e-07,-0.00031,0,0,-4.9e+02,0.0005,0.0005,0.038,0.036,0.039,0.0097,0.045,0.046,0.043,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +14090000,0.98,-0.0077,-0.011,0.18,0.017,-0.0082,0.015,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0028,-0.0023,-0.14,0.2,-2.8e-06,0.43,0.00012,7.3e-06,-0.00035,0,0,-4.9e+02,0.0005,0.0005,0.038,0.04,0.043,0.0096,0.051,0.053,0.042,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14190000,0.98,-0.0078,-0.011,0.18,0.016,-0.0076,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0039,-0.0034,-0.14,0.2,-2.6e-06,0.43,0.00018,3.3e-05,-0.00037,0,0,-4.9e+02,0.00048,0.00049,0.038,0.034,0.037,0.0094,0.045,0.046,0.042,2.1e-06,1.9e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14290000,0.98,-0.0077,-0.011,0.18,0.018,-0.0081,0.013,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.004,-0.0037,-0.14,0.2,-2.6e-06,0.43,0.00018,3.6e-05,-0.00036,0,0,-4.9e+02,0.00048,0.00049,0.038,0.038,0.041,0.0092,0.051,0.052,0.041,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14390000,0.98,-0.0078,-0.011,0.18,0.018,-0.0095,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0038,-0.0044,-0.14,0.2,-2.4e-06,0.43,0.00019,4.1e-05,-0.00035,0,0,-4.9e+02,0.00047,0.00047,0.038,0.033,0.035,0.009,0.045,0.046,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14490000,0.98,-0.008,-0.011,0.18,0.018,-0.011,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0049,-0.0045,-0.14,0.2,-2.3e-06,0.43,0.00022,5e-05,-0.00037,0,0,-4.9e+02,0.00047,0.00047,0.038,0.036,0.038,0.009,0.051,0.052,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14590000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00015,-0.0054,-0.0058,-0.14,0.2,-2.1e-06,0.43,0.00027,6.9e-05,-0.00037,0,0,-4.9e+02,0.00046,0.00046,0.038,0.031,0.033,0.0088,0.045,0.045,0.04,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14690000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0053,-0.0062,-0.14,0.2,-2e-06,0.43,0.00027,7.6e-05,-0.00037,0,0,-4.9e+02,0.00046,0.00046,0.038,0.034,0.036,0.0088,0.05,0.051,0.039,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14790000,0.98,-0.0082,-0.011,0.18,0.019,-0.0034,0.016,0,0,-4.9e+02,-0.0011,-0.0058,-0.00014,-0.0047,-0.0076,-0.14,0.2,-2.2e-06,0.43,0.00027,7.4e-05,-0.00035,0,0,-4.9e+02,0.00044,0.00045,0.038,0.03,0.031,0.0086,0.044,0.045,0.039,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14890000,0.98,-0.0082,-0.011,0.18,0.021,-0.0055,0.02,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.0093,-0.14,0.2,-1.8e-06,0.43,0.00027,9.5e-05,-0.00031,0,0,-4.9e+02,0.00045,0.00045,0.038,0.032,0.034,0.0087,0.05,0.051,0.039,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +14990000,0.98,-0.0083,-0.011,0.18,0.02,-0.0057,0.022,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0041,-0.011,-0.14,0.2,-1.6e-06,0.43,0.0003,0.00012,-0.00029,0,0,-4.9e+02,0.00044,0.00045,0.038,0.028,0.03,0.0085,0.044,0.045,0.038,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15090000,0.98,-0.0083,-0.011,0.18,0.021,-0.0049,0.026,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00013,-0.00029,0,0,-4.9e+02,0.00044,0.00045,0.038,0.031,0.032,0.0085,0.05,0.051,0.038,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15190000,0.98,-0.0085,-0.011,0.18,0.019,-0.0059,0.027,0,0,-4.9e+02,-0.0011,-0.0058,-0.00014,-0.0048,-0.012,-0.14,0.2,-1.4e-06,0.43,0.00034,0.00014,-0.00029,0,0,-4.9e+02,0.00043,0.00044,0.038,0.027,0.028,0.0085,0.044,0.045,0.038,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15290000,0.98,-0.0086,-0.012,0.18,0.022,-0.0065,0.026,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.2e-06,0.43,0.00033,0.00017,-0.00027,0,0,-4.9e+02,0.00043,0.00044,0.038,0.029,0.031,0.0085,0.049,0.05,0.037,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15390000,0.98,-0.0088,-0.011,0.18,0.021,-0.004,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0045,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,-4.9e+02,0.00042,0.00043,0.038,0.026,0.027,0.0084,0.044,0.044,0.037,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15490000,0.98,-0.0088,-0.011,0.18,0.022,-0.0067,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0046,-0.014,-0.14,0.2,-1.4e-06,0.43,0.00037,0.00019,-0.00029,0,0,-4.9e+02,0.00042,0.00043,0.038,0.028,0.029,0.0085,0.049,0.05,0.037,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15590000,0.98,-0.0088,-0.011,0.18,0.023,-0.0081,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00036,0.00019,-0.00028,0,0,-4.9e+02,0.00041,0.00043,0.038,0.024,0.026,0.0084,0.043,0.044,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15690000,0.98,-0.0086,-0.011,0.18,0.024,-0.01,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0032,-0.012,-0.14,0.2,-1.8e-06,0.43,0.00031,0.00013,-0.00026,0,0,-4.9e+02,0.00041,0.00043,0.038,0.026,0.028,0.0085,0.049,0.049,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15790000,0.98,-0.0086,-0.011,0.18,0.019,-0.0094,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0021,-0.012,-0.14,0.2,-2.2e-06,0.43,0.0003,0.00012,-0.00026,0,0,-4.9e+02,0.00041,0.00042,0.038,0.023,0.025,0.0084,0.043,0.044,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15890000,0.98,-0.0087,-0.011,0.18,0.02,-0.0085,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0031,-0.012,-0.14,0.2,-1.9e-06,0.43,0.00034,0.00015,-0.00027,0,0,-4.9e+02,0.00041,0.00042,0.038,0.025,0.027,0.0085,0.048,0.049,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15990000,0.98,-0.0086,-0.011,0.18,0.018,-0.0074,0.022,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0034,-0.014,-0.14,0.2,-2.1e-06,0.43,0.00038,0.00019,-0.00029,0,0,-4.9e+02,0.0004,0.00042,0.038,0.022,0.024,0.0084,0.043,0.043,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +16090000,0.98,-0.0087,-0.011,0.18,0.019,-0.0092,0.02,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.004,-0.014,-0.14,0.2,-2e-06,0.43,0.00041,0.00021,-0.00031,0,0,-4.9e+02,0.0004,0.00042,0.038,0.024,0.025,0.0085,0.048,0.049,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16190000,0.98,-0.0086,-0.011,0.18,0.015,-0.0076,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0047,-0.015,-0.13,0.2,-2e-06,0.43,0.00044,0.00021,-0.00033,0,0,-4.9e+02,0.0004,0.00041,0.038,0.021,0.023,0.0084,0.043,0.043,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16290000,0.98,-0.0087,-0.011,0.18,0.016,-0.009,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0044,-0.014,-0.13,0.2,-2e-06,0.43,0.00043,0.0002,-0.00032,0,0,-4.9e+02,0.0004,0.00041,0.038,0.023,0.024,0.0085,0.047,0.048,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16390000,0.98,-0.0087,-0.011,0.18,0.019,-0.0081,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.004,-0.017,-0.13,0.2,-1.7e-06,0.43,0.00045,0.00024,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.021,0.022,0.0084,0.042,0.043,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16490000,0.98,-0.0089,-0.011,0.18,0.022,-0.01,0.021,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0044,-0.017,-0.13,0.2,-1.5e-06,0.43,0.00046,0.00025,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.022,0.023,0.0085,0.047,0.048,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16590000,0.98,-0.0089,-0.011,0.18,0.025,-0.01,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0043,-0.018,-0.13,0.2,-1.7e-06,0.43,0.00048,0.00025,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.02,0.021,0.0084,0.042,0.043,0.036,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16690000,0.98,-0.0089,-0.011,0.18,0.028,-0.015,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0037,-0.017,-0.13,0.2,-1.9e-06,0.43,0.00046,0.00024,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.021,0.023,0.0085,0.047,0.047,0.036,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16790000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0031,-0.017,-0.13,0.2,-2.2e-06,0.43,0.00046,0.00024,-0.00029,0,0,-4.9e+02,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.042,0.042,0.036,1e-06,9.3e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16890000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0021,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00043,0.00023,-0.00028,0,0,-4.9e+02,0.00038,0.0004,0.038,0.02,0.022,0.0085,0.046,0.047,0.036,1e-06,9.2e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +16990000,0.98,-0.0088,-0.011,0.18,0.026,-0.013,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,-0.0018,-0.018,-0.13,0.2,-2.3e-06,0.43,0.00044,0.00025,-0.00028,0,0,-4.9e+02,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,1e-06,9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17090000,0.98,-0.0089,-0.011,0.18,0.03,-0.017,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0022,-0.019,-0.13,0.2,-2.4e-06,0.43,0.00048,0.00032,-0.00029,0,0,-4.9e+02,0.00038,0.0004,0.038,0.02,0.021,0.0085,0.046,0.047,0.035,9.9e-07,8.9e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17190000,0.98,-0.009,-0.011,0.18,0.028,-0.021,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0031,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00053,0.00033,-0.00033,0,0,-4.9e+02,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,9.6e-07,8.7e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17290000,0.98,-0.009,-0.011,0.18,0.03,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0038,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00055,0.00034,-0.00035,0,0,-4.9e+02,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.045,0.046,0.036,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17390000,0.98,-0.0089,-0.011,0.18,0.025,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0025,-0.018,-0.13,0.2,-3.2e-06,0.43,0.00053,0.00034,-0.00034,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.041,0.041,0.035,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17490000,0.98,-0.009,-0.011,0.18,0.024,-0.025,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0028,-0.019,-0.13,0.2,-3.2e-06,0.43,0.00054,0.00034,-0.00035,0,0,-4.9e+02,0.00037,0.00039,0.038,0.018,0.02,0.0085,0.045,0.046,0.036,9.3e-07,8.3e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17590000,0.98,-0.0089,-0.011,0.18,0.021,-0.022,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0024,-0.019,-0.13,0.2,-3.8e-06,0.43,0.00055,0.00034,-0.00035,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.04,0.041,0.035,9e-07,8.1e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17690000,0.98,-0.009,-0.011,0.18,0.022,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0021,-0.019,-0.13,0.2,-3.5e-06,0.43,0.00053,0.00032,-0.00033,0,0,-4.9e+02,0.00037,0.00039,0.038,0.018,0.019,0.0084,0.045,0.045,0.035,9e-07,8e-07,2e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17790000,0.98,-0.0091,-0.011,0.18,0.022,-0.022,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0013,-0.019,-0.13,0.2,-3.5e-06,0.43,0.00051,0.00029,-0.00031,0,0,-4.9e+02,0.00037,0.00039,0.038,0.016,0.017,0.0084,0.04,0.041,0.036,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17890000,0.98,-0.0089,-0.011,0.18,0.025,-0.024,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00075,-0.018,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.0003,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.019,0.0084,0.044,0.045,0.036,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17990000,0.98,-0.0089,-0.011,0.18,0.025,-0.02,0.024,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,4.1e-05,-0.02,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.00029,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0083,0.04,0.041,0.035,8.5e-07,7.6e-07,2e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +18090000,0.98,-0.009,-0.011,0.18,0.026,-0.021,0.024,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,8.7e-05,-0.02,-0.13,0.2,-3.3e-06,0.43,0.00048,0.00027,-0.00028,0,0,-4.9e+02,0.00036,0.00038,0.038,0.017,0.018,0.0083,0.044,0.045,0.036,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18190000,0.98,-0.0091,-0.011,0.18,0.025,-0.019,0.024,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0017,-0.021,-0.13,0.2,-3.6e-06,0.43,0.00045,0.00029,-0.00025,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0082,0.04,0.04,0.035,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18290000,0.98,-0.0092,-0.011,0.18,0.028,-0.02,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0018,-0.022,-0.13,0.2,-3.4e-06,0.43,0.00045,0.0003,-0.00024,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.018,0.0082,0.044,0.044,0.036,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18390000,0.98,-0.0091,-0.011,0.18,0.027,-0.019,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.002,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00046,0.00031,-0.00025,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18490000,0.98,-0.0091,-0.011,0.18,0.031,-0.019,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0027,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00045,0.00031,-0.00024,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0082,0.043,0.044,0.036,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18590000,0.98,-0.0089,-0.011,0.18,0.028,-0.019,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0029,-0.021,-0.13,0.2,-4.2e-06,0.43,0.00044,0.00028,-0.00024,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18690000,0.98,-0.0088,-0.011,0.18,0.028,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0039,-0.02,-0.13,0.2,-4.2e-06,0.43,0.00041,0.00025,-0.00022,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0081,0.043,0.044,0.035,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18790000,0.98,-0.0087,-0.011,0.18,0.026,-0.017,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0043,-0.02,-0.13,0.2,-4.6e-06,0.43,0.00041,0.00026,-0.00023,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.008,0.039,0.04,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18890000,0.98,-0.0088,-0.011,0.18,0.026,-0.018,0.018,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0041,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00043,0.00028,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.044,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +18990000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.019,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0049,-0.019,-0.13,0.2,-5.3e-06,0.43,0.00042,0.00027,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.035,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19090000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.0054,-0.019,-0.13,0.2,-5.2e-06,0.43,0.00041,0.00027,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.008,0.042,0.043,0.036,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19190000,0.98,-0.0086,-0.011,0.18,0.02,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0052,-0.019,-0.13,0.2,-6e-06,0.43,0.00043,0.00028,-0.00026,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19290000,0.98,-0.0086,-0.011,0.18,0.021,-0.019,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0052,-0.019,-0.13,0.2,-5.9e-06,0.43,0.00044,0.00029,-0.00026,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.016,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0058,-0.019,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00028,-0.00026,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,6.9e-07,6.2e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19490000,0.98,-0.0088,-0.011,0.18,0.02,-0.017,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0052,-0.02,-0.13,0.2,-6e-06,0.43,0.00043,0.00026,-0.00025,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,6.9e-07,6.1e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19590000,0.98,-0.0087,-0.011,0.18,0.018,-0.019,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0054,-0.02,-0.13,0.2,-6.2e-06,0.43,0.00043,0.00026,-0.00025,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.015,0.0076,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.03,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19690000,0.98,-0.0088,-0.011,0.18,0.018,-0.017,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0059,-0.021,-0.13,0.2,-5.9e-06,0.43,0.00043,0.00026,-0.00024,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.016,0.0076,0.042,0.043,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19790000,0.98,-0.0089,-0.011,0.18,0.015,-0.016,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0059,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19890000,0.98,-0.0089,-0.011,0.18,0.017,-0.016,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0059,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19990000,0.98,-0.0089,-0.012,0.18,0.015,-0.016,0.018,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0068,-0.021,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.038,0.038,0.035,6.4e-07,5.7e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.019,0.019,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.007,-0.021,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00028,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.4e-07,5.6e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5.1 +20190000,0.98,-0.0089,-0.012,0.18,0.017,-0.016,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00013,0.007,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00043,0.0003,-0.00027,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20290000,0.98,-0.009,-0.012,0.18,0.015,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.007,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00043,0.0003,-0.00028,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20390000,0.98,-0.0089,-0.012,0.18,0.013,-0.016,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.008,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00041,0.00028,-0.00026,0,0,-4.9e+02,0.00034,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20490000,0.98,-0.0089,-0.012,0.18,0.0094,-0.017,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0081,-0.022,-0.13,0.2,-7.3e-06,0.43,0.00041,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00035,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20590000,0.98,-0.0088,-0.012,0.18,0.0087,-0.017,0.02,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0093,-0.022,-0.13,0.2,-7.2e-06,0.43,0.00039,0.00025,-0.00025,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20690000,0.98,-0.0088,-0.012,0.18,0.0076,-0.017,0.021,0,0,-4.9e+02,-0.0013,-0.0058,-0.00012,0.009,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00039,0.00025,-0.00025,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.015,0.0072,0.041,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20790000,0.98,-0.0081,-0.012,0.18,0.0037,-0.013,0.006,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0098,-0.022,-0.13,0.2,-7.8e-06,0.43,0.00038,0.00025,-0.00025,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.8e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20890000,0.98,0.00097,-0.0077,0.18,-0.00018,-0.002,-0.11,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00038,-0.00019,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.015,0.0071,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20990000,0.98,0.0044,-0.0043,0.18,-0.012,0.017,-0.25,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00036,-0.00015,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.007,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21090000,0.98,0.0027,-0.0047,0.18,-0.024,0.032,-0.37,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-6.9e-06,0.43,0.00043,0.00016,-0.00019,0,0,-4.9e+02,0.00033,0.00035,0.038,0.014,0.015,0.007,0.04,0.041,0.035,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21190000,0.98,-6.9e-05,-0.0063,0.18,-0.03,0.039,-0.5,0,0,-4.9e+02,-0.0013,-0.0058,-0.0001,0.0099,-0.024,-0.13,0.2,-6.2e-06,0.43,0.00044,0.00019,-0.00018,0,0,-4.9e+02,0.00033,0.00034,0.038,0.013,0.014,0.0069,0.037,0.038,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21290000,0.98,-0.0023,-0.0076,0.18,-0.029,0.041,-0.63,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0095,-0.024,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00023,-0.00011,0,0,-4.9e+02,0.00033,0.00034,0.037,0.014,0.015,0.0069,0.04,0.041,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21390000,0.98,-0.0037,-0.0082,0.18,-0.026,0.038,-0.75,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0096,-0.024,-0.13,0.2,-6.3e-06,0.43,0.00044,0.00015,-0.00012,0,0,-4.9e+02,0.00032,0.00034,0.037,0.013,0.014,0.0068,0.037,0.038,0.034,5.3e-07,4.7e-07,1.7e-06,0.031,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21490000,0.98,-0.0045,-0.0086,0.18,-0.021,0.035,-0.89,0,0,-4.9e+02,-0.0013,-0.0058,-0.0001,0.01,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00044,0.00018,-0.00017,0,0,-4.9e+02,0.00032,0.00034,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21590000,0.98,-0.0049,-0.0086,0.18,-0.015,0.032,-1,0,0,-4.9e+02,-0.0013,-0.0058,-9.5e-05,0.01,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00042,0.00023,-0.00018,0,0,-4.9e+02,0.00032,0.00034,0.037,0.013,0.015,0.0067,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21690000,0.98,-0.0052,-0.0085,0.18,-0.012,0.027,-1.1,0,0,-4.9e+02,-0.0013,-0.0058,-8.7e-05,0.011,-0.024,-0.13,0.2,-6.3e-06,0.43,0.00039,0.00027,-0.00017,0,0,-4.9e+02,0.00032,0.00034,0.037,0.014,0.016,0.0067,0.04,0.041,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21790000,0.98,-0.0055,-0.0086,0.18,-0.0066,0.022,-1.3,0,0,-4.9e+02,-0.0013,-0.0058,-7.8e-05,0.012,-0.023,-0.13,0.2,-6.3e-06,0.43,0.00039,0.00027,-0.00022,0,0,-4.9e+02,0.00032,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21890000,0.98,-0.0058,-0.0088,0.18,-0.003,0.017,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-8.1e-05,0.012,-0.023,-0.13,0.2,-6.7e-06,0.43,0.00037,0.00029,-0.00021,0,0,-4.9e+02,0.00032,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21990000,0.98,-0.0064,-0.009,0.18,-0.00094,0.013,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-7.5e-05,0.012,-0.022,-0.13,0.2,-6.4e-06,0.43,0.0004,0.0003,-0.00023,0,0,-4.9e+02,0.00031,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22090000,0.98,-0.0071,-0.0099,0.18,0.0011,0.0095,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.6e-05,0.012,-0.022,-0.13,0.2,-6.3e-06,0.43,0.00039,0.00032,-0.00024,0,0,-4.9e+02,0.00031,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22190000,0.98,-0.0075,-0.01,0.18,0.0069,0.0051,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.8e-05,0.013,-0.02,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00033,-0.00024,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.014,0.0065,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22290000,0.98,-0.0082,-0.01,0.18,0.013,-0.00055,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6e-05,0.013,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00033,-0.00023,0,0,-4.9e+02,0.00031,0.00032,0.037,0.014,0.015,0.0065,0.04,0.041,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22390000,0.98,-0.0085,-0.01,0.18,0.017,-0.0091,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.2e-05,0.012,-0.02,-0.13,0.2,-6.5e-06,0.43,0.00041,0.00033,-0.00026,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.014,0.0064,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22490000,0.98,-0.0087,-0.011,0.18,0.021,-0.016,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.6e-05,0.011,-0.02,-0.13,0.2,-6.9e-06,0.43,0.00041,0.00035,-0.00028,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22590000,0.98,-0.0086,-0.012,0.18,0.029,-0.024,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.8e-05,0.012,-0.02,-0.13,0.2,-6.4e-06,0.43,0.00042,0.00037,-0.00027,0,0,-4.9e+02,0.0003,0.00032,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.028,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6e-05,0.011,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00042,0.00037,-0.00029,0,0,-4.9e+02,0.0003,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.036,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.4e-05,0.011,-0.021,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00034,-0.00031,0,0,-4.9e+02,0.0003,0.00031,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22890000,0.98,-0.0087,-0.012,0.18,0.042,-0.041,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.5e-05,0.011,-0.021,-0.13,0.2,-6.2e-06,0.43,0.00041,0.00035,-0.00029,0,0,-4.9e+02,0.0003,0.00031,0.037,0.013,0.015,0.0063,0.04,0.041,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.046,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.6e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00032,-0.00027,0,0,-4.9e+02,0.0003,0.00031,0.037,0.012,0.014,0.0062,0.036,0.038,0.033,4.3e-07,3.9e-07,1.6e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23090000,0.98,-0.0086,-0.013,0.18,0.051,-0.05,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00039,0.00033,-0.00025,0,0,-4.9e+02,0.0003,0.00031,0.037,0.013,0.014,0.0062,0.04,0.041,0.033,4.3e-07,3.9e-07,1.5e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23190000,0.98,-0.0086,-0.013,0.18,0.057,-0.052,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.9e-05,0.012,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00037,0.0003,-0.00025,0,0,-4.9e+02,0.00029,0.00031,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23290000,0.98,-0.0091,-0.014,0.18,0.062,-0.057,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.012,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00034,0.00034,-0.00025,0,0,-4.9e+02,0.00029,0.00031,0.037,0.013,0.014,0.0062,0.039,0.041,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23390000,0.98,-0.009,-0.014,0.18,0.066,-0.06,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.9e-05,0.012,-0.019,-0.13,0.2,-7.7e-06,0.43,0.00035,0.00032,-0.00023,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23490000,0.98,-0.0091,-0.014,0.18,0.072,-0.062,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.1e-05,0.012,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00034,0.00037,-0.00028,0,0,-4.9e+02,0.00029,0.0003,0.037,0.013,0.014,0.0061,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23590000,0.98,-0.0093,-0.014,0.18,0.075,-0.064,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.7e-05,0.013,-0.019,-0.13,0.2,-8.4e-06,0.43,0.00029,0.00034,-0.00024,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.006,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23690000,0.98,-0.01,-0.015,0.18,0.074,-0.066,-1.3,0,0,-4.9e+02,-0.0013,-0.0058,-3.9e-05,0.013,-0.02,-0.13,0.2,-8.2e-06,0.43,0.00027,0.00036,-0.00024,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.014,0.006,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23790000,0.98,-0.012,-0.017,0.18,0.068,-0.062,-0.95,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.014,-0.02,-0.13,0.2,-7.9e-06,0.43,0.00026,0.00039,-0.00022,0,0,-4.9e+02,0.00029,0.0003,0.037,0.011,0.013,0.006,0.036,0.037,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23890000,0.98,-0.015,-0.021,0.18,0.064,-0.062,-0.52,0,0,-4.9e+02,-0.0013,-0.0058,-3.5e-05,0.014,-0.02,-0.13,0.2,-7.9e-06,0.43,0.00024,0.00042,-0.00024,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.006,0.039,0.041,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23990000,0.98,-0.017,-0.024,0.18,0.063,-0.061,-0.13,0,0,-4.9e+02,-0.0013,-0.0058,-4.2e-05,0.015,-0.02,-0.13,0.2,-8e-06,0.43,0.00021,0.00043,3.6e-06,0,0,-4.9e+02,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.033,3.9e-07,3.5e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24090000,0.98,-0.017,-0.023,0.18,0.07,-0.069,0.099,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.015,-0.019,-0.13,0.2,-8e-06,0.43,0.00022,0.0004,3.6e-06,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24190000,0.98,-0.014,-0.019,0.18,0.08,-0.074,0.089,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.017,-0.02,-0.13,0.2,-7.6e-06,0.43,0.00022,0.00037,0.0001,0,0,-4.9e+02,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.032,3.8e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24290000,0.98,-0.012,-0.016,0.18,0.084,-0.078,0.067,0,0,-4.9e+02,-0.0013,-0.0058,-4.3e-05,0.017,-0.02,-0.13,0.2,-7.2e-06,0.43,0.00026,0.00032,9.8e-05,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24390000,0.98,-0.011,-0.015,0.18,0.077,-0.073,0.083,0,0,-4.9e+02,-0.0013,-0.0058,-4.1e-05,0.018,-0.02,-0.13,0.2,-5.9e-06,0.43,0.00025,0.00037,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24490000,0.98,-0.011,-0.015,0.18,0.073,-0.069,0.081,0,0,-4.9e+02,-0.0013,-0.0058,-2.8e-05,0.019,-0.021,-0.13,0.2,-5.9e-06,0.43,0.00017,0.00047,0.00021,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24590000,0.98,-0.012,-0.015,0.18,0.069,-0.066,0.077,0,0,-4.9e+02,-0.0013,-0.0058,-3.9e-05,0.02,-0.021,-0.13,0.2,-4.6e-06,0.43,0.00021,0.00044,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24690000,0.98,-0.012,-0.015,0.18,0.067,-0.065,0.076,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.02,-0.021,-0.13,0.2,-4.8e-06,0.43,0.0002,0.00047,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24790000,0.98,-0.012,-0.014,0.18,0.064,-0.063,0.068,0,0,-4.9e+02,-0.0014,-0.0058,-4.5e-05,0.022,-0.022,-0.13,0.2,-4.2e-06,0.43,0.00019,0.00048,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24890000,0.98,-0.012,-0.014,0.18,0.063,-0.067,0.057,0,0,-4.9e+02,-0.0014,-0.0058,-4e-05,0.022,-0.022,-0.13,0.2,-4e-06,0.43,0.00019,0.00049,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24990000,0.98,-0.012,-0.014,0.18,0.055,-0.063,0.05,0,0,-4.9e+02,-0.0014,-0.0058,-5.4e-05,0.023,-0.023,-0.13,0.2,-4.2e-06,0.43,0.00015,0.00059,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25090000,0.98,-0.012,-0.014,0.18,0.051,-0.063,0.048,0,0,-4.9e+02,-0.0014,-0.0058,-5.4e-05,0.024,-0.023,-0.13,0.2,-4.8e-06,0.43,0.00014,0.00067,0.00029,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25190000,0.98,-0.012,-0.014,0.18,0.045,-0.057,0.048,0,0,-4.9e+02,-0.0014,-0.0058,-7.2e-05,0.025,-0.024,-0.13,0.2,-4.8e-06,0.43,0.00012,0.0007,0.00028,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25290000,0.98,-0.012,-0.013,0.18,0.041,-0.059,0.043,0,0,-4.9e+02,-0.0014,-0.0058,-7.9e-05,0.025,-0.024,-0.13,0.2,-5.4e-06,0.43,0.00011,0.00072,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25390000,0.98,-0.012,-0.013,0.18,0.032,-0.052,0.041,0,0,-4.9e+02,-0.0014,-0.0058,-9.4e-05,0.027,-0.025,-0.13,0.2,-6.2e-06,0.43,7.1e-05,0.00078,0.00026,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25490000,0.98,-0.013,-0.013,0.18,0.028,-0.053,0.041,0,0,-4.9e+02,-0.0014,-0.0058,-9.6e-05,0.026,-0.025,-0.13,0.2,-5.9e-06,0.43,6.5e-05,0.00073,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25590000,0.98,-0.013,-0.012,0.18,0.023,-0.049,0.042,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-6.7e-06,0.43,3.4e-05,0.00076,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25690000,0.98,-0.012,-0.012,0.18,0.023,-0.048,0.031,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-6.8e-06,0.43,4e-05,0.00079,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25790000,0.98,-0.012,-0.012,0.18,0.011,-0.04,0.031,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.029,-0.026,-0.13,0.2,-7.3e-06,0.43,-2.1e-05,0.00072,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25890000,0.98,-0.012,-0.012,0.18,0.0059,-0.039,0.033,0,0,-4.9e+02,-0.0014,-0.0058,-0.00013,0.029,-0.026,-0.13,0.2,-7.5e-06,0.43,-4e-05,0.00069,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25990000,0.98,-0.012,-0.012,0.18,-0.0031,-0.032,0.027,0,0,-4.9e+02,-0.0014,-0.0058,-0.00015,0.031,-0.026,-0.13,0.2,-8.9e-06,0.43,-9.5e-05,0.00067,0.00014,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26090000,0.98,-0.012,-0.012,0.18,-0.0077,-0.032,0.025,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.031,-0.027,-0.13,0.2,-8.4e-06,0.43,-9.2e-05,0.00066,0.00017,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26190000,0.98,-0.012,-0.012,0.18,-0.015,-0.025,0.021,0,0,-4.9e+02,-0.0015,-0.0058,-0.00014,0.032,-0.026,-0.13,0.2,-8.7e-06,0.43,-0.00012,0.00066,0.00019,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26290000,0.98,-0.012,-0.013,0.18,-0.015,-0.024,0.015,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,0.032,-0.027,-0.13,0.2,-9.3e-06,0.43,-0.00012,0.00067,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26390000,0.98,-0.011,-0.013,0.18,-0.021,-0.017,0.019,0,0,-4.9e+02,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1e-05,0.43,-0.00016,0.00065,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26490000,0.98,-0.011,-0.013,0.18,-0.023,-0.015,0.028,0,0,-4.9e+02,-0.0015,-0.0058,-0.00016,0.033,-0.028,-0.13,0.2,-1.1e-05,0.43,-0.00017,0.00068,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26590000,0.98,-0.01,-0.013,0.18,-0.026,-0.0064,0.029,0,0,-4.9e+02,-0.0015,-0.0058,-0.00017,0.033,-0.028,-0.13,0.2,-1.2e-05,0.43,-0.00019,0.0007,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26690000,0.98,-0.01,-0.012,0.18,-0.027,-0.0023,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00021,0.00071,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.0019,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00023,0.00069,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26890000,0.98,-0.0092,-0.012,0.18,-0.04,0.0048,0.022,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.2e-05,0.43,-0.00023,0.00067,0.00011,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.012,0.021,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00065,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27090000,0.98,-0.0086,-0.013,0.18,-0.05,0.018,0.025,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.035,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00065,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27190000,0.98,-0.0086,-0.013,0.18,-0.056,0.025,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00026,0.00064,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27290000,0.98,-0.0088,-0.014,0.18,-0.063,0.03,0.14,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00027,0.00064,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0054,0.038,0.039,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27390000,0.98,-0.01,-0.016,0.18,-0.07,0.037,0.46,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.5e-05,0.43,-0.00033,0.00057,0.00018,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27490000,0.98,-0.012,-0.018,0.18,-0.074,0.043,0.78,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.0003,0.00053,0.00018,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.013,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27590000,0.98,-0.011,-0.017,0.18,-0.069,0.046,0.87,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00048,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27690000,0.98,-0.01,-0.014,0.18,-0.065,0.042,0.78,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.5e-05,0.43,-0.00027,0.00047,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27790000,0.98,-0.0088,-0.012,0.18,-0.065,0.041,0.77,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00043,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27890000,0.98,-0.0085,-0.013,0.18,-0.071,0.047,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00043,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27990000,0.98,-0.0089,-0.013,0.18,-0.072,0.049,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00037,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28090000,0.98,-0.0092,-0.013,0.18,-0.076,0.05,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00039,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28190000,0.98,-0.0086,-0.013,0.18,-0.077,0.047,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.033,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00038,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28290000,0.98,-0.0081,-0.013,0.18,-0.081,0.051,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.00018,0.034,-0.029,-0.12,0.2,-1.5e-05,0.43,-0.00027,0.0004,0.00019,0,0,-4.9e+02,0.00029,0.00029,0.037,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.033,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00031,0.00031,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28490000,0.98,-0.0084,-0.015,0.18,-0.084,0.058,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00028,0.0003,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28590000,0.98,-0.0085,-0.014,0.18,-0.078,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00025,0.00028,0.00022,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28690000,0.98,-0.0082,-0.014,0.18,-0.078,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00022,0.00028,0.00022,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28790000,0.98,-0.0076,-0.014,0.18,-0.076,0.056,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00015,0.032,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.00018,0.00022,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28890000,0.98,-0.0074,-0.013,0.18,-0.08,0.058,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.032,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00025,0.00021,0.0002,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28990000,0.98,-0.0072,-0.013,0.18,-0.077,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.031,-0.029,-0.12,0.2,-1.8e-05,0.43,-0.00028,6.7e-05,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29090000,0.98,-0.007,-0.013,0.18,-0.08,0.057,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.0003,4.9e-05,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29190000,0.98,-0.0069,-0.014,0.18,-0.078,0.056,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.03,-0.029,-0.12,0.2,-2e-05,0.43,-0.00033,-8.1e-05,0.00024,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29290000,0.98,-0.0072,-0.014,0.18,-0.081,0.062,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00032,-0.0001,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29390000,0.98,-0.0076,-0.013,0.18,-0.077,0.061,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00036,-0.00023,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.8e-07,2.6e-07,9.9e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29490000,0.98,-0.0076,-0.013,0.18,-0.08,0.062,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.0001,0.029,-0.028,-0.12,0.2,-2.1e-05,0.43,-0.00038,-0.0002,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29590000,0.98,-0.0075,-0.013,0.18,-0.077,0.061,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-8.6e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00043,-0.00031,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29690000,0.98,-0.0075,-0.013,0.18,-0.082,0.06,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-7.9e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00045,-0.00027,0.00021,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29790000,0.98,-0.0073,-0.013,0.18,-0.079,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-6.3e-05,0.027,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.0005,-0.00039,0.00021,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29890000,0.98,-0.0068,-0.013,0.18,-0.08,0.056,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.7e-05,0.028,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.00052,-0.00036,0.00019,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29990000,0.98,-0.007,-0.013,0.18,-0.075,0.051,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-4.5e-05,0.026,-0.029,-0.12,0.2,-2.6e-05,0.43,-0.00051,-0.00041,0.00021,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.5e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30090000,0.98,-0.0071,-0.013,0.18,-0.077,0.051,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.6e-05,0.026,-0.029,-0.12,0.2,-2.7e-05,0.43,-0.00046,-0.00048,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.4e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30190000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.8e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00046,-0.00069,0.00032,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30290000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.7e-05,0.026,-0.029,-0.12,0.2,-2.8e-05,0.43,-0.0005,-0.00074,0.00032,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30390000,0.98,-0.0071,-0.013,0.18,-0.065,0.043,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-3.9e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00064,-0.00095,0.00032,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30490000,0.98,-0.0071,-0.013,0.18,-0.068,0.043,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-3.3e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00068,-0.00094,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30590000,0.98,-0.0074,-0.014,0.18,-0.064,0.041,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.8e-05,0.024,-0.03,-0.12,0.2,-3e-05,0.43,-0.00079,-0.001,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.1e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30690000,0.98,-0.0078,-0.014,0.18,-0.062,0.04,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.7e-05,0.025,-0.03,-0.12,0.2,-3e-05,0.43,-0.00076,-0.00099,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.5e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30790000,0.98,-0.0075,-0.013,0.17,-0.056,0.034,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.3e-05,0.024,-0.031,-0.12,0.2,-3.1e-05,0.43,-0.00084,-0.0012,0.00033,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30890000,0.98,-0.0069,-0.013,0.17,-0.056,0.031,0.79,0,0,-4.9e+02,-0.0014,-0.0058,-2e-05,0.024,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00075,-0.0011,0.00035,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30990000,0.98,-0.0071,-0.013,0.17,-0.049,0.025,0.8,0,0,-4.9e+02,-0.0014,-0.0057,-1.3e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00078,-0.0012,0.00038,0,0,-4.9e+02,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31090000,0.98,-0.0073,-0.013,0.17,-0.048,0.024,0.79,0,0,-4.9e+02,-0.0014,-0.0057,-1.7e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00073,-0.0012,0.00039,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31190000,0.98,-0.0075,-0.013,0.17,-0.043,0.02,0.8,0,0,-4.9e+02,-0.0013,-0.0057,-1.2e-06,0.023,-0.033,-0.12,0.2,-3.4e-05,0.43,-0.00083,-0.0012,0.00039,0,0,-4.9e+02,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31290000,0.98,-0.0077,-0.014,0.17,-0.04,0.018,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3.9e-06,0.024,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00086,-0.0011,0.00037,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31390000,0.98,-0.0075,-0.013,0.17,-0.035,0.011,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3.2e-06,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.00095,-0.0015,0.00042,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31490000,0.98,-0.0073,-0.014,0.17,-0.036,0.0081,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.5e-06,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.001,-0.0017,0.00043,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31590000,0.98,-0.0071,-0.014,0.17,-0.033,0.0062,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.1e-05,0.023,-0.034,-0.12,0.2,-3.1e-05,0.43,-0.0011,-0.0018,0.00045,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.5e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31690000,0.98,-0.0071,-0.014,0.17,-0.036,0.0056,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.9e-05,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.0012,-0.0018,0.00043,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31790000,0.98,-0.0074,-0.015,0.17,-0.026,0.003,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.4e-05,0.023,-0.034,-0.12,0.2,-3e-05,0.43,-0.0013,-0.0019,0.00045,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31890000,0.99,-0.0071,-0.015,0.17,-0.025,0.0008,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.8e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.002,0.00047,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31990000,0.99,-0.0074,-0.014,0.17,-0.017,-0.00029,0.79,0,0,-4.9e+02,-0.0013,-0.0057,2.5e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0022,0.00053,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32090000,0.99,-0.0077,-0.014,0.17,-0.019,-0.0037,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.6e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0022,0.00054,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32190000,0.99,-0.008,-0.014,0.17,-0.013,-0.0073,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.1e-05,0.024,-0.035,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0024,0.00058,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32290000,0.99,-0.0079,-0.014,0.17,-0.013,-0.0099,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.6e-05,0.024,-0.034,-0.12,0.2,-2.8e-05,0.43,-0.0015,-0.0025,0.00059,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32390000,0.99,-0.008,-0.015,0.17,-0.0063,-0.012,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.3e-05,0.025,-0.035,-0.12,0.2,-2.6e-05,0.43,-0.0016,-0.0027,0.00065,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32490000,0.99,-0.011,-0.012,0.17,0.018,-0.077,-0.076,0,0,-4.9e+02,-0.0013,-0.0057,1.9e-05,0.025,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0015,-0.0026,0.00064,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.014,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32590000,0.99,-0.011,-0.013,0.17,0.021,-0.079,-0.079,0,0,-4.9e+02,-0.0013,-0.0057,1.9e-05,0.025,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32690000,0.99,-0.011,-0.012,0.17,0.016,-0.085,-0.08,0,0,-4.9e+02,-0.0013,-0.0057,1.8e-05,0.025,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32790000,0.99,-0.011,-0.013,0.17,0.017,-0.084,-0.081,0,0,-4.9e+02,-0.0013,-0.0057,1.6e-05,0.025,-0.035,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0022,0.00078,0,0,-4.9e+02,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32890000,0.99,-0.011,-0.013,0.17,0.017,-0.09,-0.083,0,0,-4.9e+02,-0.0013,-0.0057,2e-05,0.025,-0.035,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0021,0.00079,0,0,-4.9e+02,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32990000,0.98,-0.011,-0.013,0.17,0.017,-0.089,-0.082,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.025,-0.035,-0.12,0.2,-2.3e-05,0.43,-0.0015,-0.002,0.00085,0,0,-4.9e+02,0.00027,0.00027,0.035,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +33090000,0.98,-0.011,-0.013,0.17,0.013,-0.093,-0.079,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.025,-0.035,-0.12,0.2,-2.3e-05,0.43,-0.0015,-0.002,0.00085,0,0,-4.9e+02,0.00027,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +33190000,0.98,-0.01,-0.013,0.17,0.011,-0.094,-0.078,0,0,-4.9e+02,-0.0014,-0.0057,1.3e-05,0.026,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0015,-0.002,0.00088,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33290000,0.98,-0.01,-0.013,0.17,0.0073,-0.096,-0.078,0,0,-4.9e+02,-0.0014,-0.0057,2.3e-05,0.026,-0.034,-0.12,0.2,-2e-05,0.43,-0.0016,-0.002,0.00092,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33390000,0.98,-0.01,-0.013,0.17,0.0051,-0.09,-0.076,0,0,-4.9e+02,-0.0014,-0.0057,1.6e-05,0.028,-0.033,-0.12,0.2,-1.8e-05,0.43,-0.0016,-0.002,0.00096,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.033 +33490000,0.98,-0.01,-0.013,0.17,-0.00023,-0.093,-0.075,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.028,-0.032,-0.12,0.2,-1.6e-05,0.43,-0.0017,-0.0021,0.00099,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.058 +33590000,0.98,-0.01,-0.013,0.17,-0.003,-0.092,-0.072,0,0,-4.9e+02,-0.0014,-0.0057,2e-05,0.029,-0.032,-0.12,0.2,-1.3e-05,0.43,-0.0018,-0.0022,0.001,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.083 +33690000,0.98,-0.01,-0.013,0.17,-0.0063,-0.095,-0.073,0,0,-4.9e+02,-0.0014,-0.0057,2.4e-05,0.029,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.0018,-0.002,0.001,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.11 +33790000,0.98,-0.01,-0.013,0.17,-0.0082,-0.092,-0.068,0,0,-4.9e+02,-0.0014,-0.0057,1.4e-05,0.031,-0.032,-0.12,0.2,-1.2e-05,0.43,-0.0017,-0.0018,0.0011,0,0,-4.9e+02,0.00027,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.13 +33890000,0.98,-0.01,-0.013,0.17,-0.012,-0.093,-0.067,0,0,-4.9e+02,-0.0014,-0.0057,2.4e-05,0.031,-0.032,-0.12,0.2,-1.1e-05,0.43,-0.0018,-0.0018,0.0011,0,0,-4.9e+02,0.00027,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.4e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.16 +33990000,0.98,-0.0099,-0.013,0.17,-0.013,-0.088,-0.064,0,0,-4.9e+02,-0.0014,-0.0057,1.2e-05,0.033,-0.031,-0.12,0.2,-8.4e-06,0.43,-0.0017,-0.0018,0.0011,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.18 +34090000,0.98,-0.0098,-0.013,0.17,-0.017,-0.093,-0.062,0,0,-4.9e+02,-0.0014,-0.0057,1.5e-05,0.033,-0.031,-0.12,0.2,-8.8e-06,0.43,-0.0017,-0.0017,0.0011,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.21 +34190000,0.98,-0.0098,-0.013,0.17,-0.018,-0.088,-0.06,0,0,-4.9e+02,-0.0014,-0.0057,1e-05,0.035,-0.031,-0.12,0.2,-6.4e-06,0.43,-0.0016,-0.0015,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.23 +34290000,0.98,-0.0096,-0.013,0.17,-0.019,-0.092,-0.058,0,0,-4.9e+02,-0.0014,-0.0057,1.7e-05,0.035,-0.031,-0.12,0.2,-5.7e-06,0.43,-0.0017,-0.0016,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.26 +34390000,0.98,-0.0095,-0.013,0.17,-0.021,-0.085,-0.054,0,0,-4.9e+02,-0.0014,-0.0056,9.9e-06,0.036,-0.03,-0.12,0.2,-3.6e-06,0.43,-0.0016,-0.0015,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.28 +34490000,0.98,-0.0095,-0.013,0.17,-0.024,-0.089,-0.052,0,0,-4.9e+02,-0.0014,-0.0056,1.8e-05,0.036,-0.03,-0.12,0.2,-3.3e-06,0.43,-0.0017,-0.0014,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.31 +34590000,0.98,-0.0094,-0.013,0.17,-0.026,-0.081,0.74,0,0,-4.9e+02,-0.0014,-0.0056,1.1e-05,0.038,-0.03,-0.12,0.2,-8.1e-07,0.43,-0.0016,-0.0014,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 +34690000,0.98,-0.0094,-0.013,0.17,-0.03,-0.079,1.7,0,0,-4.9e+02,-0.0014,-0.0056,1.4e-05,0.038,-0.03,-0.12,0.2,-5.2e-07,0.43,-0.0017,-0.0014,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.36 +34790000,0.98,-0.0093,-0.013,0.17,-0.033,-0.07,2.7,0,0,-4.9e+02,-0.0015,-0.0056,7.9e-06,0.04,-0.031,-0.12,0.2,2.1e-06,0.43,-0.0017,-0.0013,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 +34890000,0.98,-0.0092,-0.013,0.17,-0.038,-0.069,3.7,0,0,-4.9e+02,-0.0015,-0.0056,1.1e-05,0.04,-0.031,-0.12,0.2,2.2e-06,0.43,-0.0017,-0.0013,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 From efa9f3de9c3b7fde9d94de1d0f35e78ad9a296da Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 22 Nov 2024 09:20:19 +0100 Subject: [PATCH 05/11] ekf2: update earth rate also without GNSS --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 15 --------------- .../ekf2/EKF/aid_sources/gnss/gps_control.cpp | 6 ++++-- src/modules/ekf2/EKF/ekf.cpp | 5 +++++ src/modules/ekf2/EKF/ekf.h | 2 -- 4 files changed, 9 insertions(+), 19 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp index c1b47c224fa7..e21ee82ff9f2 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -55,21 +55,6 @@ #define MASK_GPS_VSPD (1<<8) #define MASK_GPS_SPOOFED (1<<9) -void Ekf::collect_gps(const gnssSample &gps) -{ - if (_filter_initialised && !_local_origin_lat_lon.isInitialized() && _gps_checks_passed) { - _information_events.flags.gps_checks_passed = true; - - } else { - // a rough 2D fix is sufficient to lookup earth spin rate - const bool gps_rough_2d_fix = (gps.fix_type >= 2) && (gps.hacc < 1000); - - if (gps_rough_2d_fix && (_gps_checks_passed || !_local_origin_lat_lon.isInitialized())) { - _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); - } - } -} - bool Ekf::runGnssChecks(const gnssSample &gps) { _gps_check_fail_status.flags.spoofed = gps.spoofed; diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp index de8dad37b5e8..889af97a08ce 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_control.cpp @@ -67,11 +67,13 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed) && isTimedOut(_last_gps_fail_us, max((uint64_t)1e6, (uint64_t)_min_gps_health_time_us / 10))) { if (isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us)) { // First time checks are passing, latching. + if (!_gps_checks_passed) { + _information_events.flags.gps_checks_passed = true; + } + _gps_checks_passed = true; } - collect_gps(gnss_sample); - } else { // Skip this sample _gps_data_ready = false; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index e1fb96784fd6..d883d83ff8be 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -230,6 +230,11 @@ bool Ekf::initialiseTilt() void Ekf::predictState(const imuSample &imu_delayed) { + if (std::fabs(_gpos.latitude_rad() - _earth_rate_lat_ref_rad) > math::radians(1.0)) { + _earth_rate_lat_ref_rad = _gpos.latitude_rad(); + _earth_rate_NED = calcEarthRateNED((float)_earth_rate_lat_ref_rad); + } + // apply imu bias corrections const Vector3f delta_ang_bias_scaled = getGyroBias() * imu_delayed.delta_ang_dt; Vector3f corrected_delta_ang = imu_delayed.delta_ang - delta_ang_bias_scaled; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index a76c0e351782..c2277606b108 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -374,8 +374,6 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_EXTERNAL_VISION #if defined(CONFIG_EKF2_GNSS) - void collect_gps(const gnssSample &gps); - // set minimum continuous period without GPS fail required to mark a healthy GPS status void set_min_required_gps_health_time(uint32_t time_us) { _min_gps_health_time_us = time_us; } From da8020139249935897a4fb4ed6fe267152cff5a5 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 22 Nov 2024 09:21:23 +0100 Subject: [PATCH 06/11] ekf2: compensate for coriolis and transport rate accelerations --- src/modules/ekf2/EKF/ekf.cpp | 7 +++++-- src/modules/ekf2/EKF/ekf.h | 3 ++- src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp | 15 +++++++++++++++ 3 files changed, 22 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index d883d83ff8be..c3d4434a714d 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -259,8 +259,11 @@ void Ekf::predictState(const imuSample &imu_delayed) // calculate the increment in velocity using the current orientation _state.vel += corrected_delta_vel_ef; - // compensate for acceleration due to gravity - _state.vel(2) += CONSTANTS_ONE_G * imu_delayed.delta_vel_dt; + // compensate for acceleration due to gravity, Coriolis and transport rate + const Vector3f gravity_acceleration(0.f, 0.f, CONSTANTS_ONE_G); // simplistic model + const Vector3f coriolis_acceleration = -2.f * _earth_rate_NED.cross(vel_last); + const Vector3f transport_rate = -_gpos.computeAngularRateNavFrame(vel_last).cross(vel_last); + _state.vel += (gravity_acceleration + coriolis_acceleration + transport_rate) * imu_delayed.delta_vel_dt; // predict position states via trapezoidal integration of velocity _gpos += (vel_last + _state.vel) * imu_delayed.delta_vel_dt * 0.5f; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index c2277606b108..47c6e10f94b6 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -487,7 +487,8 @@ class Ekf final : public EstimatorInterface LatLonAlt _last_known_gpos{}; - Vector3f _earth_rate_NED{}; ///< earth rotation vector (NED) in rad/s + Vector3f _earth_rate_NED{}; ///< earth rotation vector (NED) in rad/s + double _earth_rate_lat_ref_rad{0.0}; ///< latitude at which the earth rate was evaluated (radians) Dcmf _R_to_earth{}; ///< transformation matrix from body frame to earth frame from last EKF prediction diff --git a/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp index 0fa7115df77a..bb6a384d6ac6 100644 --- a/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp +++ b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp @@ -120,6 +120,21 @@ class LatLonAlt -delta_alt); } + /* + * Compute the angular rate of the local navigation frame at the current latitude and height + * with respect to an inertial frame and resolved in the navigation frame + */ + matrix::Vector3f computeAngularRateNavFrame(const matrix::Vector3f &v_ned) + { + double r_n; + double r_e; + computeRadiiOfCurvature(_latitude_rad, r_n, r_e); + return matrix::Vector3f( + v_ned(1) / (static_cast(r_e) + _altitude), + -v_ned(0) / (static_cast(r_n) + _altitude), + -v_ned(1) * tanf(_latitude_rad) / (static_cast(r_e) + _altitude)); + } + private: // Convert between curvilinear and cartesian errors static matrix::Vector2d deltaLatLonToDeltaXY(const double latitude, const float altitude) From 1fcdeb005e3f3bb7b4fcdd8968dc3fbd363d544a Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 1 Nov 2024 15:15:19 +0100 Subject: [PATCH 07/11] update change indicator --- .../test/change_indication/ekf_gsf_reset.csv | 748 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 664 ++++++++-------- 2 files changed, 706 insertions(+), 706 deletions(-) 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 fcf346c1e89d..fbc6d2b054a5 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -14,378 +14,378 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0,0,-1.2e+02,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0,0,-1.2e+02,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0,0,-1.2e+02,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -1490000,1,-0.01,-0.014,0.00016,0.024,0.0029,-0.16,0,0,-1.2e+02,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0,0,-1.2e+02,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0,0,-1.2e+02,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.011,-0.014,0.00013,0.028,-0.00014,-0.19,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.011,-0.014,9.8e-05,0.035,-0.002,-0.2,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.011,-0.015,7.8e-05,0.043,-0.0033,-0.22,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,8.9e-05,0.036,-0.0048,-0.23,0,0,-1.2e+02,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 -2090000,1,-0.011,-0.014,5.1e-05,0.041,-0.0073,-0.24,0,0,-1.2e+02,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,6.4e-05,0.033,-0.007,-0.26,0,0,-1.2e+02,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,5.1e-05,0.039,-0.0095,-0.27,0,0,-1.2e+02,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,6.9e-05,0.03,-0.0089,-0.29,0,0,-1.2e+02,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.013,5.1e-05,0.035,-0.011,-0.3,0,0,-1.2e+02,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.011,-0.013,6.6e-05,0.026,-0.0093,-0.31,0,0,-1.2e+02,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.011,-0.013,6.3e-05,0.03,-0.011,-0.33,0,0,-1.2e+02,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.011,-0.013,5.8e-05,0.023,-0.0096,-0.34,0,0,-1.2e+02,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.011,-0.013,8.3e-06,0.027,-0.012,-0.35,0,0,-1.2e+02,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.011,-0.013,5.6e-05,0.022,-0.0098,-0.36,0,0,-1.2e+02,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.011,-0.013,6e-05,0.025,-0.011,-0.38,0,0,-1.2e+02,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.011,-0.013,2.9e-06,0.02,-0.009,-0.39,0,0,-1.2e+02,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.011,-0.013,4.4e-05,0.023,-0.011,-0.4,0,0,-1.2e+02,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.011,-0.012,1.5e-05,0.018,-0.0095,-0.42,0,0,-1.2e+02,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.011,-0.013,8.2e-06,0.022,-0.012,-0.43,0,0,-1.2e+02,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.011,-0.012,3.2e-05,0.017,-0.011,-0.44,0,0,-1.2e+02,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.011,-0.012,0.00015,0.019,-0.014,-0.46,0,0,-1.2e+02,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.011,-0.012,0.0002,0.016,-0.014,-0.47,0,0,-1.2e+02,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.48,0,0,-1.2e+02,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.011,-0.012,0.00017,0.02,-0.017,-0.5,0,0,-1.2e+02,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.51,0,0,-1.2e+02,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.011,-0.012,0.00014,0.02,-0.017,-0.53,0,0,-1.2e+02,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.01,-0.012,9.8e-05,0.017,-0.012,-0.54,0,0,-1.2e+02,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.01,-0.012,0.00012,0.018,-0.013,-0.55,0,0,-1.2e+02,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.01,-0.012,0.00018,0.014,-0.01,-0.57,0,0,-1.2e+02,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.01,-0.012,0.00021,0.017,-0.012,-0.58,0,0,-1.2e+02,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.01,-0.012,0.00021,0.014,-0.01,-0.6,0,0,-1.2e+02,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.01,-0.012,0.0002,0.015,-0.012,-0.61,0,0,-1.2e+02,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.01,-0.011,0.00019,0.012,-0.01,-0.63,0,0,-1.2e+02,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.01,-0.012,0.00017,0.015,-0.011,-0.64,0,0,-1.2e+02,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.01,-0.011,0.00022,0.011,-0.0085,-0.66,0,0,-1.2e+02,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.01,-0.011,0.00024,0.013,-0.0098,-0.67,0,0,-1.2e+02,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.01,-0.011,0.00023,0.0086,-0.0073,-0.68,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0099,-0.011,0.00029,0.0081,-0.0081,-0.7,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0098,-0.011,0.0003,0.0055,-0.0062,-0.71,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0097,-0.011,0.00028,0.0061,-0.0066,-0.73,0,0,-1.2e+02,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0096,-0.011,0.00036,0.0041,-0.0038,-0.74,0,0,-1.2e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0095,-0.011,0.00035,0.0044,-0.0028,-0.75,0,0,-1.2e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0095,-0.011,0.00033,0.0038,-0.00092,0.0028,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0094,-0.011,0.00036,0.0041,0.00056,0.015,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-4.9e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0094,-0.011,0.00034,0.0051,0.0017,-0.011,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-4.9e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0094,-0.011,0.00027,0.0038,0.0042,-0.005,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0094,-0.011,0.00024,0.005,0.0043,-0.012,0,0,-4.9e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-4.9e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0093,-0.011,0.00026,0.0043,0.0053,-0.05,0,0,-4.9e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-4.9e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0093,-0.011,0.00026,0.0049,0.0055,-0.052,0,0,-4.9e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.0093,-0.011,0.00019,0.0037,0.0055,-0.099,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0093,-0.011,0.00012,0.0046,0.0051,-0.076,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,0.71,0.0012,-0.014,0.71,0.0049,0.0051,-0.11,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,-6.9e-05,0.21,8e-05,0.43,3.6e-05,0.00032,-0.0024,0,0,-4.9e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.11,0.11,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 -6890000,0.71,0.0013,-0.014,0.7,0.00053,0.0064,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,0,0,-9.7e-05,0.21,1.3e-05,0.43,1.3e-06,0.00089,-0.00086,0,0,-4.9e+02,0.0013,0.0013,0.047,0.21,0.21,0.46,0.13,0.14,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 -6990000,0.71,0.0013,-0.014,0.71,-0.00023,0.0046,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.6e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.044,0.23,0.24,0.36,0.17,0.17,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 -7090000,0.71,0.0012,-0.014,0.71,-0.00079,0.0011,-0.13,0,0,-4.9e+02,-0.0014,-0.0057,-7.7e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00037,0.00025,-0.00041,0,0,-4.9e+02,0.0013,0.0013,0.043,0.27,0.27,0.29,0.2,0.21,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 -7190000,0.71,0.0013,-0.014,0.71,-0.0025,0.0019,-0.15,0,0,-4.9e+02,-0.0015,-0.0057,-7.7e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-4.9e+02,0.0013,0.0013,0.042,0.3,0.31,0.24,0.25,0.25,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 -7290000,0.71,0.0015,-0.014,0.71,-0.0044,0.0099,-0.15,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00021,-0.0002,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00039,0,0,-4.9e+02,0.0013,0.0013,0.042,0.34,0.35,0.2,0.3,0.31,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7390000,0.71,0.0016,-0.014,0.71,-0.0037,0.015,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00028,-3.8e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00032,0,0,-4.9e+02,0.0013,0.0013,0.041,0.38,0.39,0.18,0.37,0.37,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7490000,0.71,0.0015,-0.014,0.71,-0.0038,0.011,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00018,-7.3e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00078,-0.00043,0,0,-4.9e+02,0.0013,0.0013,0.041,0.43,0.43,0.15,0.44,0.45,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7590000,0.71,0.0016,-0.014,0.71,-0.0034,0.02,-0.17,0,0,-4.9e+02,-0.0017,-0.0057,-6.8e-05,-0.00024,0.00021,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-4.9e+02,0.0013,0.0013,0.04,0.48,0.48,0.14,0.53,0.53,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 -7690000,0.71,0.0016,-0.014,0.71,-0.0046,0.017,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00032,0.00084,-0.00033,0,0,-4.9e+02,0.0014,0.0013,0.04,0.53,0.53,0.13,0.63,0.63,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 -7790000,0.71,0.0017,-0.014,0.71,-0.011,0.016,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00036,6.2e-05,-0.0071,0.21,-1.6e-05,0.43,-0.00034,0.00078,-0.00038,0,0,-4.9e+02,0.0014,0.0013,0.04,0.58,0.58,0.12,0.74,0.74,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 -7890000,0.71,0.0017,-0.014,0.71,-0.011,0.021,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00038,0.0002,-0.0096,0.21,-1.5e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-4.9e+02,0.0014,0.0014,0.04,0.64,0.63,0.11,0.87,0.86,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 -7990000,0.71,0.0017,-0.014,0.71,-0.0091,0.022,-0.16,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00037,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00086,-0.00038,0,0,-4.9e+02,0.0014,0.0014,0.04,0.7,0.68,0.1,1,0.99,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 -8090000,0.71,0.0017,-0.014,0.71,-0.005,0.024,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-6.7e-05,-0.0003,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00033,0.0009,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.04,0.76,0.74,0.1,1.2,1.1,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8190000,0.71,0.0017,-0.014,0.71,-0.014,0.028,-0.18,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00043,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-4.9e+02,0.0014,0.0014,0.04,0.82,0.79,0.099,1.4,1.3,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8290000,0.71,0.0017,-0.014,0.71,-0.017,0.021,-0.17,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00056,0.00031,-0.017,0.21,-1e-05,0.43,-0.00031,0.00079,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.039,0.88,0.84,0.097,1.6,1.5,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8390000,0.71,0.0017,-0.014,0.71,-0.0012,0.00041,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.021,0.21,-9.3e-06,0.43,-0.0003,0.00084,-0.00031,0,0,-4.9e+02,0.0014,0.0014,0.039,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,7e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 -8490000,0.71,0.0017,-0.014,0.71,-0.003,0.0023,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.025,0.21,-9e-06,0.43,-0.00031,0.0008,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.089,6.2e-05,6.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8590000,0.71,0.0021,-0.014,0.71,-0.00044,0.00093,-0.17,0,0,-4.9e+02,-0.0018,-0.0057,-6.8e-05,-0.00051,0.00039,-0.029,0.21,-1.2e-05,0.43,-0.00042,0.00076,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.088,6e-05,6.8e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8690000,0.71,0.002,-0.014,0.71,-0.0034,0.0028,-0.16,0,0,-4.9e+02,-0.0017,-0.0056,-6.6e-05,-0.00051,0.00039,-0.035,0.21,-1e-05,0.43,-0.00039,0.00084,-0.00029,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.088,5.8e-05,6.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8790000,0.71,0.0019,-0.014,0.71,-0.0057,0.0049,-0.15,0,0,-4.9e+02,-0.0017,-0.0057,-6.9e-05,-0.0005,0.00043,-0.041,0.21,-9.1e-06,0.43,-0.00037,0.0008,-0.00029,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.087,5.6e-05,6.6e-05,2.4e-06,0.04,0.04,0.032,0.0013,6.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 -8890000,0.71,0.0019,-0.014,0.71,-0.0079,0.0055,-0.15,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00063,0.00042,-0.045,0.21,-7.8e-06,0.43,-0.00034,0.00078,-0.00033,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.086,5.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.03,0.0013,6.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -8990000,0.71,0.0018,-0.014,0.71,-0.01,0.0049,-0.14,0,0,-4.9e+02,-0.0015,-0.0058,-7.5e-05,-0.00087,0.00044,-0.051,0.21,-6.6e-06,0.43,-0.0003,0.00071,-0.00034,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.087,5.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.029,0.0013,6.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -9090000,0.71,0.002,-0.014,0.71,-0.014,0.006,-0.14,0,0,-4.9e+02,-0.0016,-0.0058,-7.6e-05,-0.00098,0.00054,-0.053,0.21,-6.9e-06,0.43,-0.00033,0.00068,-0.00034,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1.1e+02,1.1e+02,0.086,4.9e-05,6.2e-05,2.4e-06,0.04,0.04,0.028,0.0013,5.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -9190000,0.71,0.0019,-0.014,0.71,-0.012,0.0087,-0.14,0,0,-4.9e+02,-0.0015,-0.0056,-7e-05,-0.00086,0.00059,-0.057,0.21,-6.2e-06,0.43,-0.00031,0.00081,-0.00025,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.094,1.1e+02,1.1e+02,0.085,4.6e-05,6e-05,2.4e-06,0.04,0.04,0.027,0.0013,5.6e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 -9290000,0.71,0.0017,-0.014,0.71,-0.011,0.0086,-0.14,0,0,-4.9e+02,-0.0015,-0.0056,-7.1e-05,-0.00096,0.00059,-0.061,0.21,-5.1e-06,0.43,-0.00026,0.00082,-0.00024,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.093,1.1e+02,1.1e+02,0.085,4.4e-05,5.8e-05,2.4e-06,0.04,0.04,0.025,0.0013,5.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9390000,0.71,0.0015,-0.014,0.71,-0.011,0.0092,-0.14,0,0,-4.9e+02,-0.0014,-0.0056,-7.3e-05,-0.001,0.00058,-0.065,0.21,-4.3e-06,0.43,-0.00022,0.00082,-0.00022,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.093,1.2e+02,1.2e+02,0.086,4.2e-05,5.7e-05,2.4e-06,0.04,0.04,0.024,0.0013,5.2e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9490000,0.71,0.0014,-0.014,0.71,-0.0078,0.011,-0.13,0,0,-4.9e+02,-0.0014,-0.0055,-6.9e-05,-0.001,0.0006,-0.068,0.21,-3.7e-06,0.43,-0.00018,0.0009,-0.00013,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.091,1.2e+02,1.2e+02,0.085,4e-05,5.5e-05,2.4e-06,0.04,0.04,0.023,0.0013,5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9590000,0.71,0.0016,-0.014,0.71,-0.01,0.016,-0.13,0,0,-4.9e+02,-0.0015,-0.0054,-6.6e-05,-0.0011,0.00079,-0.072,0.21,-4.5e-06,0.43,-0.00024,0.00091,-0.00012,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.09,1.3e+02,1.3e+02,0.085,3.8e-05,5.4e-05,2.4e-06,0.04,0.04,0.021,0.0013,4.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 -9690000,0.71,0.0018,-0.014,0.71,-0.017,0.017,-0.12,0,0,-4.9e+02,-0.0015,-0.0056,-7e-05,-0.0013,0.00092,-0.077,0.21,-4.8e-06,0.43,-0.00027,0.0008,-0.00017,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.089,1.3e+02,1.3e+02,0.086,3.6e-05,5.2e-05,2.4e-06,0.04,0.04,0.02,0.0013,4.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -9790000,0.71,0.0017,-0.014,0.71,-0.013,0.02,-0.11,0,0,-4.9e+02,-0.0015,-0.0055,-6.8e-05,-0.0014,0.001,-0.082,0.21,-4.4e-06,0.43,-0.00024,0.00085,-9.7e-05,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.087,1.4e+02,1.4e+02,0.085,3.4e-05,5e-05,2.4e-06,0.04,0.04,0.019,0.0013,4.5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -9890000,0.71,0.0018,-0.014,0.71,-0.016,0.023,-0.11,0,0,-4.9e+02,-0.0015,-0.0055,-6.8e-05,-0.0015,0.0011,-0.085,0.21,-4.6e-06,0.43,-0.00026,0.00083,-0.0001,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.084,1.4e+02,1.4e+02,0.085,3.2e-05,4.9e-05,2.4e-06,0.04,0.04,0.018,0.0013,4.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -9990000,0.71,0.0019,-0.014,0.71,-0.02,0.021,-0.1,0,0,-4.9e+02,-0.0015,-0.0056,-7.1e-05,-0.0016,0.0011,-0.089,0.21,-4.2e-06,0.43,-0.00025,0.00078,-0.00013,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.083,1.5e+02,1.5e+02,0.086,3e-05,4.7e-05,2.4e-06,0.04,0.04,0.017,0.0013,4.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 -10090000,0.71,0.002,-0.014,0.71,-0.022,0.025,-0.096,0,0,-4.9e+02,-0.0015,-0.0056,-6.9e-05,-0.0017,0.0013,-0.091,0.21,-4.6e-06,0.43,-0.00029,0.00079,-0.00012,0,0,-4.9e+02,0.0013,0.0012,0.039,25,25,0.08,1.6e+02,1.6e+02,0.085,2.9e-05,4.6e-05,2.4e-06,0.04,0.04,0.016,0.0013,4.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10190000,0.71,0.002,-0.013,0.71,-0.033,0.022,-0.096,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,-0.0019,0.0013,-0.093,0.21,-4.5e-06,0.43,-0.00027,0.00065,-0.00015,0,0,-4.9e+02,0.0012,0.0012,0.039,25,25,0.078,1.7e+02,1.7e+02,0.084,2.7e-05,4.4e-05,2.4e-06,0.04,0.04,0.014,0.0013,4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10290000,0.71,0.002,-0.013,0.71,-0.04,0.017,-0.084,0,0,-4.9e+02,-0.0015,-0.0058,-7.8e-05,-0.0021,0.0014,-0.098,0.21,-4.2e-06,0.43,-0.00026,0.00058,-0.00017,0,0,-4.9e+02,0.0012,0.0012,0.039,25,25,0.076,1.8e+02,1.8e+02,0.085,2.6e-05,4.2e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10390000,0.71,0.0018,-0.013,0.71,0.0091,-0.02,0.0093,0,0,-4.9e+02,-0.0015,-0.0058,-7.9e-05,-0.0021,0.0013,-0.098,0.21,-3.7e-06,0.43,-0.00023,0.0006,-0.00014,0,0,-4.9e+02,0.0012,0.0012,0.039,0.25,0.25,0.56,0.5,0.5,0.077,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10490000,0.71,0.0018,-0.013,0.71,0.0071,-0.019,0.022,0,0,-4.9e+02,-0.0014,-0.0059,-8.3e-05,-0.0022,0.0013,-0.098,0.21,-3.3e-06,0.43,-0.00021,0.00053,-0.00016,0,0,-4.9e+02,0.0012,0.0012,0.039,0.26,0.26,0.55,0.51,0.51,0.079,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10590000,0.71,0.0022,-0.013,0.71,0.006,-0.0082,0.024,0,0,-4.9e+02,-0.0016,-0.0059,-7.9e-05,-0.0024,0.0018,-0.098,0.21,-4.5e-06,0.43,-0.00029,0.00053,-0.00017,0,0,-4.9e+02,0.0012,0.0011,0.039,0.13,0.13,0.27,0.17,0.17,0.072,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10690000,0.71,0.0021,-0.013,0.71,0.0033,-0.009,0.027,0,0,-4.9e+02,-0.0015,-0.0059,-8.1e-05,-0.0024,0.0018,-0.098,0.21,-4.1e-06,0.43,-0.00027,0.00052,-0.00017,0,0,-4.9e+02,0.0012,0.0011,0.039,0.14,0.14,0.26,0.18,0.18,0.077,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10790000,0.71,0.002,-0.013,0.71,0.0034,-0.0064,0.021,0,0,-4.9e+02,-0.0015,-0.0059,-8e-05,-0.0025,0.0021,-0.098,0.21,-4e-06,0.43,-0.00026,0.00056,-0.00016,0,0,-4.9e+02,0.0012,0.0011,0.038,0.093,0.094,0.17,0.11,0.11,0.071,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10890000,0.71,0.0019,-0.013,0.71,0.0021,-0.0066,0.016,0,0,-4.9e+02,-0.0015,-0.0058,-8.1e-05,-0.0025,0.0021,-0.098,0.21,-3.7e-06,0.43,-0.00025,0.00057,-0.00015,0,0,-4.9e+02,0.0011,0.0011,0.038,0.1,0.1,0.16,0.11,0.11,0.074,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -10990000,0.71,0.0017,-0.014,0.71,0.0068,-0.0015,0.011,0,0,-4.9e+02,-0.0013,-0.0057,-7.9e-05,-0.0025,0.0031,-0.098,0.21,-3.2e-06,0.43,-0.00022,0.00071,-0.00011,0,0,-4.9e+02,0.0011,0.001,0.038,0.079,0.08,0.12,0.079,0.079,0.071,1.7e-05,3.1e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11090000,0.71,0.0017,-0.014,0.71,0.0068,0.0018,0.014,0,0,-4.9e+02,-0.0014,-0.0056,-7.5e-05,-0.0023,0.0029,-0.098,0.21,-3.3e-06,0.43,-0.00023,0.00078,-6.8e-05,0,0,-4.9e+02,0.0011,0.00099,0.038,0.09,0.091,0.12,0.085,0.085,0.073,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11190000,0.71,0.0017,-0.014,0.71,0.01,0.0034,0.0027,0,0,-4.9e+02,-0.0013,-0.0056,-7.8e-05,-0.0023,0.004,-0.098,0.21,-3.4e-06,0.43,-0.00024,0.00079,-8.6e-05,0,0,-4.9e+02,0.00098,0.00092,0.038,0.074,0.075,0.091,0.066,0.066,0.068,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11290000,0.71,0.0016,-0.014,0.71,0.0094,0.0018,0.0014,0,0,-4.9e+02,-0.0013,-0.0057,-8.3e-05,-0.0026,0.0043,-0.098,0.21,-3e-06,0.43,-0.00022,0.00073,-0.00011,0,0,-4.9e+02,0.00098,0.00091,0.038,0.086,0.087,0.087,0.072,0.072,0.071,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11390000,0.71,0.0016,-0.013,0.71,0.0049,0.00087,-0.0044,0,0,-4.9e+02,-0.0013,-0.0058,-8.6e-05,-0.0033,0.0041,-0.098,0.21,-3e-06,0.43,-0.00021,0.00066,-0.00016,0,0,-4.9e+02,0.00087,0.00082,0.038,0.072,0.073,0.072,0.058,0.058,0.067,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11490000,0.71,0.0014,-0.013,0.71,0.0011,-0.002,-0.0044,0,0,-4.9e+02,-0.0012,-0.0059,-9.3e-05,-0.0039,0.0049,-0.098,0.21,-2.7e-06,0.43,-0.00018,0.00056,-0.00022,0,0,-4.9e+02,0.00086,0.00081,0.038,0.083,0.086,0.069,0.064,0.064,0.068,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11590000,0.71,0.0013,-0.013,0.71,-0.002,-0.0015,-0.01,0,0,-4.9e+02,-0.0012,-0.0059,-9.4e-05,-0.0045,0.005,-0.098,0.21,-2.5e-06,0.43,-0.00016,0.00054,-0.00023,0,0,-4.9e+02,0.00075,0.00072,0.038,0.07,0.072,0.059,0.054,0.054,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11690000,0.71,0.0011,-0.013,0.71,-0.0035,-0.0027,-0.016,0,0,-4.9e+02,-0.0011,-0.006,-9.8e-05,-0.0053,0.0052,-0.098,0.21,-2e-06,0.43,-0.0001,0.00053,-0.00026,0,0,-4.9e+02,0.00075,0.00071,0.038,0.082,0.084,0.057,0.06,0.06,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11790000,0.71,0.0011,-0.013,0.71,-0.0075,-0.00084,-0.018,0,0,-4.9e+02,-0.0011,-0.006,-9.9e-05,-0.0071,0.0053,-0.098,0.21,-2e-06,0.43,-8.6e-05,0.0005,-0.00027,0,0,-4.9e+02,0.00065,0.00063,0.038,0.068,0.07,0.051,0.051,0.051,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11890000,0.71,0.00095,-0.013,0.71,-0.0085,-0.0037,-0.02,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0078,0.0059,-0.098,0.21,-1.9e-06,0.43,-5.4e-05,0.00047,-0.00032,0,0,-4.9e+02,0.00065,0.00062,0.038,0.08,0.082,0.049,0.058,0.058,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11990000,0.71,0.0013,-0.013,0.71,-0.012,0.0012,-0.026,0,0,-4.9e+02,-0.0011,-0.006,-9.9e-05,-0.0074,0.0064,-0.097,0.21,-2.9e-06,0.43,-0.00013,0.00048,-0.00032,0,0,-4.9e+02,0.00056,0.00055,0.037,0.066,0.068,0.045,0.049,0.049,0.062,9.2e-06,1.6e-05,2.3e-06,0.026,0.028,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -12090000,0.71,0.0014,-0.013,0.71,-0.013,0.0044,-0.032,0,0,-4.9e+02,-0.0012,-0.0059,-9.5e-05,-0.0063,0.0056,-0.097,0.21,-3e-06,0.43,-0.00016,0.00053,-0.00028,0,0,-4.9e+02,0.00056,0.00055,0.037,0.077,0.079,0.045,0.056,0.057,0.062,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12190000,0.71,0.0012,-0.013,0.71,-0.0068,0.004,-0.026,0,0,-4.9e+02,-0.0011,-0.0059,-9.6e-05,-0.0062,0.006,-0.099,0.21,-2.3e-06,0.43,-0.00011,0.0006,-0.00026,0,0,-4.9e+02,0.00048,0.00048,0.037,0.064,0.066,0.041,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12290000,0.71,0.001,-0.013,0.71,-0.0081,0.0044,-0.026,0,0,-4.9e+02,-0.0011,-0.0059,-9.6e-05,-0.0067,0.0056,-0.099,0.21,-2e-06,0.43,-8.1e-05,0.0006,-0.00026,0,0,-4.9e+02,0.00048,0.00048,0.037,0.073,0.076,0.042,0.056,0.056,0.06,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12390000,0.71,0.001,-0.013,0.71,-0.0053,0.0032,-0.023,0,0,-4.9e+02,-0.0011,-0.0059,-9.9e-05,-0.0053,0.0073,-0.1,0.21,-2.5e-06,0.43,-0.00012,0.00061,-0.00025,0,0,-4.9e+02,0.00042,0.00043,0.037,0.061,0.063,0.039,0.048,0.048,0.058,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12490000,0.71,0.00093,-0.013,0.71,-0.007,0.0028,-0.027,0,0,-4.9e+02,-0.0011,-0.0059,-0.0001,-0.0058,0.0085,-0.1,0.21,-2.7e-06,0.43,-0.00015,0.00054,-0.00025,0,0,-4.9e+02,0.00042,0.00042,0.037,0.069,0.072,0.04,0.055,0.055,0.058,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12590000,0.71,0.0011,-0.013,0.71,-0.014,0.0037,-0.033,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0051,0.0078,-0.1,0.21,-3e-06,0.43,-0.00019,0.00051,-0.00024,0,0,-4.9e+02,0.00037,0.00038,0.037,0.058,0.059,0.038,0.047,0.048,0.057,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12690000,0.71,0.0014,-0.013,0.71,-0.017,0.0046,-0.037,0,0,-4.9e+02,-0.0012,-0.006,-0.0001,-0.0034,0.0091,-0.1,0.21,-3.9e-06,0.43,-0.00026,0.0005,-0.00025,0,0,-4.9e+02,0.00037,0.00038,0.037,0.065,0.067,0.039,0.055,0.055,0.057,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12790000,0.71,0.0012,-0.013,0.71,-0.02,0.0027,-0.041,0,0,-4.9e+02,-0.0012,-0.006,-0.0001,-0.0049,0.008,-0.1,0.21,-3.3e-06,0.43,-0.0002,0.00048,-0.00027,0,0,-4.9e+02,0.00033,0.00034,0.037,0.054,0.056,0.037,0.047,0.047,0.056,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12890000,0.71,0.0011,-0.013,0.71,-0.019,0.0014,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0063,0.0076,-0.1,0.21,-2.8e-06,0.43,-0.00017,0.00047,-0.00026,0,0,-4.9e+02,0.00033,0.00034,0.037,0.061,0.063,0.038,0.054,0.055,0.057,6e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -12990000,0.71,0.001,-0.013,0.71,-0.009,0.0019,-0.039,0,0,-4.9e+02,-0.0011,-0.0059,-9.9e-05,-0.0039,0.008,-0.1,0.21,-2.7e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-4.9e+02,0.0003,0.00031,0.037,0.051,0.053,0.037,0.047,0.047,0.055,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13090000,0.71,0.00094,-0.013,0.71,-0.0097,-0.00016,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.005,0.0096,-0.1,0.21,-3e-06,0.43,-0.00019,0.00052,-0.00023,0,0,-4.9e+02,0.0003,0.00031,0.037,0.057,0.059,0.038,0.054,0.054,0.056,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13190000,0.71,0.00094,-0.013,0.71,-0.0023,0.0008,-0.034,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0032,0.011,-0.11,0.21,-3.4e-06,0.43,-0.00023,0.00056,-0.00021,0,0,-4.9e+02,0.00027,0.00029,0.037,0.048,0.05,0.037,0.047,0.047,0.054,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13290000,0.71,0.00079,-0.013,0.71,-0.00082,0.0015,-0.029,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0047,0.0096,-0.11,0.21,-2.5e-06,0.43,-0.00017,0.00058,-0.0002,0,0,-4.9e+02,0.00027,0.00028,0.037,0.054,0.055,0.038,0.054,0.054,0.055,5.1e-06,8.9e-06,2.3e-06,0.015,0.019,0.0097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13390000,0.71,0.0007,-0.013,0.71,0.00021,0.0023,-0.024,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0042,0.0088,-0.11,0.21,-2.3e-06,0.43,-0.00016,0.00063,-0.00019,0,0,-4.9e+02,0.00025,0.00026,0.037,0.045,0.047,0.037,0.047,0.047,0.054,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13490000,0.71,0.0007,-0.013,0.71,0.00018,0.0024,-0.022,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0042,0.0081,-0.11,0.21,-1.9e-06,0.43,-0.00014,0.00063,-0.00017,0,0,-4.9e+02,0.00025,0.00026,0.037,0.05,0.052,0.038,0.054,0.054,0.055,4.7e-06,8.2e-06,2.3e-06,0.014,0.018,0.009,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13590000,0.71,0.00072,-0.013,0.71,-5.1e-05,0.0028,-0.024,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.004,0.0093,-0.11,0.21,-2.4e-06,0.43,-0.00017,0.00062,-0.00019,0,0,-4.9e+02,0.00023,0.00025,0.037,0.042,0.044,0.037,0.046,0.047,0.054,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13690000,0.71,0.0007,-0.013,0.71,0.00087,0.0053,-0.029,0,0,-4.9e+02,-0.001,-0.0059,-9.9e-05,-0.0035,0.0081,-0.11,0.21,-2e-06,0.43,-0.00016,0.00064,-0.00016,0,0,-4.9e+02,0.00023,0.00024,0.037,0.047,0.049,0.038,0.053,0.054,0.055,4.3e-06,7.7e-06,2.3e-06,0.013,0.017,0.0083,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13790000,0.71,0.00074,-0.013,0.71,0.00057,0.0021,-0.03,0,0,-4.9e+02,-0.0011,-0.0059,-9.9e-05,-0.002,0.0088,-0.11,0.21,-2.4e-06,0.43,-0.00019,0.00065,-0.00015,0,0,-4.9e+02,0.00022,0.00023,0.037,0.04,0.041,0.036,0.046,0.046,0.053,4.2e-06,7.3e-06,2.3e-06,0.013,0.016,0.0078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13890000,0.71,0.00059,-0.013,0.71,0.0024,0.0021,-0.035,0,0,-4.9e+02,-0.001,-0.0059,-9.8e-05,-0.0034,0.0077,-0.11,0.21,-1.7e-06,0.43,-0.00015,0.00065,-0.00015,0,0,-4.9e+02,0.00022,0.00023,0.037,0.044,0.046,0.037,0.053,0.053,0.055,4e-06,7.1e-06,2.3e-06,0.012,0.016,0.0076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13990000,0.71,0.00065,-0.013,0.71,0.0018,0.0005,-0.034,0,0,-4.9e+02,-0.001,-0.0059,-9.8e-05,-0.0021,0.0083,-0.11,0.21,-2e-06,0.43,-0.00018,0.00065,-0.00013,0,0,-4.9e+02,0.00021,0.00022,0.037,0.037,0.039,0.036,0.046,0.046,0.054,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0071,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -14090000,0.71,0.00072,-0.013,0.71,0.0014,0.0019,-0.035,0,0,-4.9e+02,-0.0011,-0.0059,-9.4e-05,-0.00064,0.0072,-0.11,0.21,-1.8e-06,0.43,-0.00018,0.00068,-9.7e-05,0,0,-4.9e+02,0.00021,0.00022,0.037,0.041,0.043,0.036,0.053,0.053,0.054,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14190000,0.71,0.00068,-0.013,0.71,0.0044,0.0018,-0.037,0,0,-4.9e+02,-0.0011,-0.0059,-9.3e-05,-0.00018,0.007,-0.11,0.21,-1.6e-06,0.43,-0.00017,0.0007,-8e-05,0,0,-4.9e+02,0.0002,0.00021,0.037,0.035,0.037,0.035,0.046,0.046,0.054,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14290000,0.71,0.00075,-0.013,0.71,0.0046,0.0032,-0.035,0,0,-4.9e+02,-0.0011,-0.0058,-9.2e-05,0.00066,0.0069,-0.11,0.21,-1.7e-06,0.43,-0.00019,0.00071,-6.2e-05,0,0,-4.9e+02,0.0002,0.00021,0.037,0.039,0.04,0.036,0.052,0.052,0.055,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14390000,0.71,0.00063,-0.014,0.71,0.007,0.0049,-0.037,0,0,-4.9e+02,-0.0011,-0.0058,-8.9e-05,0.00034,0.0054,-0.11,0.21,-9e-07,0.43,-0.00015,0.00074,-4.6e-05,0,0,-4.9e+02,0.00019,0.0002,0.037,0.033,0.035,0.034,0.046,0.046,0.053,3.4e-06,6e-06,2.3e-06,0.011,0.014,0.0059,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14490000,0.71,0.00052,-0.013,0.71,0.008,0.0064,-0.041,0,0,-4.9e+02,-0.001,-0.0058,-8.9e-05,-0.00096,0.0049,-0.11,0.21,-4.1e-07,0.43,-0.00013,0.0007,-4.6e-05,0,0,-4.9e+02,0.00019,0.0002,0.037,0.036,0.038,0.035,0.052,0.052,0.054,3.3e-06,5.8e-06,2.3e-06,0.011,0.014,0.0057,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14590000,0.71,0.00042,-0.013,0.71,0.006,0.0049,-0.041,0,0,-4.9e+02,-0.001,-0.0058,-8.9e-05,-0.0019,0.0047,-0.11,0.21,-3.2e-07,0.43,-0.00012,0.00067,-5.9e-05,0,0,-4.9e+02,0.00018,0.00019,0.037,0.031,0.033,0.033,0.045,0.045,0.054,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0053,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14690000,0.71,0.00037,-0.013,0.71,0.0078,0.003,-0.038,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.0018,0.0038,-0.11,0.21,6.3e-08,0.43,-0.0001,0.00068,-4.6e-05,0,0,-4.9e+02,0.00018,0.00019,0.037,0.034,0.036,0.034,0.051,0.052,0.054,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14790000,0.71,0.00035,-0.013,0.71,0.0055,0.0016,-0.033,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.002,0.0036,-0.12,0.21,7.8e-09,0.43,-0.0001,0.00066,-4.7e-05,0,0,-4.9e+02,0.00017,0.00018,0.037,0.03,0.031,0.032,0.045,0.045,0.053,3e-06,5.2e-06,2.3e-06,0.0098,0.013,0.0048,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14890000,0.71,0.00032,-0.013,0.71,0.0077,0.0033,-0.037,0,0,-4.9e+02,-0.001,-0.0058,-8.6e-05,-0.0022,0.0031,-0.12,0.21,2.7e-07,0.43,-9e-05,0.00067,-4.4e-05,0,0,-4.9e+02,0.00017,0.00018,0.037,0.032,0.034,0.032,0.051,0.051,0.055,2.9e-06,5.1e-06,2.3e-06,0.0097,0.013,0.0046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -14990000,0.71,0.00027,-0.013,0.71,0.0067,0.0023,-0.032,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.0028,0.0036,-0.12,0.21,7.5e-08,0.43,-9.9e-05,0.00064,-5.6e-05,0,0,-4.9e+02,0.00017,0.00017,0.037,0.028,0.03,0.031,0.045,0.045,0.053,2.8e-06,4.9e-06,2.3e-06,0.0094,0.013,0.0043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15090000,0.71,0.0002,-0.013,0.71,0.0075,0.0024,-0.035,0,0,-4.9e+02,-0.001,-0.0058,-8.8e-05,-0.0029,0.004,-0.12,0.21,-2.8e-08,0.43,-0.00011,0.00063,-5.7e-05,0,0,-4.9e+02,0.00017,0.00017,0.037,0.031,0.032,0.031,0.05,0.051,0.054,2.7e-06,4.8e-06,2.3e-06,0.0093,0.012,0.0041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15190000,0.71,0.00016,-0.013,0.7,0.0072,0.003,-0.033,0,0,-4.9e+02,-0.001,-0.0058,-9e-05,-0.0035,0.0043,-0.12,0.21,-2.3e-08,0.43,-0.00012,0.00059,-6.4e-05,0,0,-4.9e+02,0.00016,0.00017,0.037,0.027,0.028,0.03,0.044,0.045,0.053,2.6e-06,4.6e-06,2.3e-06,0.0091,0.012,0.0038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15290000,0.71,0.00019,-0.013,0.7,0.0077,0.0041,-0.03,0,0,-4.9e+02,-0.001,-0.0058,-8.8e-05,-0.0026,0.0041,-0.12,0.21,2.1e-08,0.43,-0.00014,0.00059,-4e-05,0,0,-4.9e+02,0.00016,0.00017,0.037,0.029,0.031,0.03,0.05,0.05,0.054,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15390000,0.71,0.0002,-0.013,0.7,0.007,0.0053,-0.028,0,0,-4.9e+02,-0.001,-0.0058,-8.3e-05,-0.0018,0.0027,-0.12,0.21,3.7e-07,0.43,-0.00012,0.00062,-1.7e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.025,0.027,0.028,0.044,0.044,0.053,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15490000,0.71,0.00021,-0.013,0.7,0.0085,0.0045,-0.028,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.0022,0.004,-0.12,0.21,-8e-08,0.43,-0.00014,0.00059,-3.5e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.027,0.029,0.029,0.049,0.05,0.054,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15590000,0.71,0.00018,-0.013,0.71,0.0071,0.0035,-0.027,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.0028,0.0047,-0.12,0.21,-4.3e-07,0.43,-0.00014,0.00058,-6.1e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.024,0.026,0.027,0.044,0.044,0.053,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15690000,0.71,0.00022,-0.013,0.71,0.0074,0.0036,-0.028,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.0023,0.0051,-0.12,0.21,-7.3e-07,0.43,-0.00015,0.00058,-6.4e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.026,0.028,0.027,0.049,0.049,0.053,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15790000,0.71,0.00019,-0.013,0.7,0.008,0.002,-0.03,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.0026,0.0053,-0.12,0.21,-8.4e-07,0.43,-0.00016,0.00057,-6.8e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.023,0.025,0.026,0.043,0.044,0.052,2.2e-06,3.9e-06,2.3e-06,0.0082,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15890000,0.71,0.0002,-0.013,0.71,0.0087,0.0021,-0.028,0,0,-4.9e+02,-0.0011,-0.0059,-8.8e-05,-0.0018,0.0056,-0.12,0.21,-1e-06,0.43,-0.00018,0.00057,-6e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.025,0.027,0.026,0.048,0.049,0.053,2.1e-06,3.8e-06,2.3e-06,0.0081,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15990000,0.71,0.00017,-0.013,0.71,0.0085,0.0022,-0.024,0,0,-4.9e+02,-0.0011,-0.0059,-8.4e-05,-0.0012,0.0049,-0.12,0.21,-9.4e-07,0.43,-0.00018,0.00058,-4.2e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.022,0.024,0.025,0.043,0.043,0.052,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -16090000,0.71,0.00021,-0.013,0.71,0.01,0.0038,-0.02,0,0,-4.9e+02,-0.0011,-0.0058,-8e-05,-0.00044,0.0036,-0.12,0.21,-6.7e-07,0.43,-0.00016,0.00063,-2.6e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.024,0.026,0.024,0.048,0.049,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16190000,0.71,0.00026,-0.013,0.71,0.01,0.004,-0.019,0,0,-4.9e+02,-0.0011,-0.0058,-7.9e-05,0.0003,0.0038,-0.12,0.21,-9.9e-07,0.43,-0.00017,0.00063,-2.1e-05,0,0,-4.9e+02,0.00015,0.00014,0.037,0.021,0.023,0.023,0.043,0.043,0.052,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16290000,0.71,0.00028,-0.014,0.71,0.012,0.0051,-0.02,0,0,-4.9e+02,-0.0011,-0.0058,-7.5e-05,0.00062,0.0025,-0.12,0.21,-5.3e-07,0.43,-0.00015,0.00064,-5.9e-06,0,0,-4.9e+02,0.00015,0.00014,0.037,0.023,0.025,0.023,0.048,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16390000,0.71,0.00033,-0.013,0.71,0.01,0.0036,-0.019,0,0,-4.9e+02,-0.0011,-0.0058,-7.6e-05,0.0017,0.0037,-0.12,0.21,-1.3e-06,0.43,-0.00018,0.00064,-2e-06,0,0,-4.9e+02,0.00014,0.00014,0.037,0.02,0.023,0.022,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0075,0.0098,0.002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16490000,0.71,0.00042,-0.013,0.71,0.0087,0.0049,-0.022,0,0,-4.9e+02,-0.0011,-0.0058,-7.5e-05,0.0026,0.0039,-0.12,0.21,-1.5e-06,0.43,-0.00019,0.00064,1.2e-05,0,0,-4.9e+02,0.00014,0.00014,0.037,0.022,0.024,0.022,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0019,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16590000,0.71,0.00052,-0.013,0.71,0.0066,0.0058,-0.023,0,0,-4.9e+02,-0.0012,-0.0058,-7.6e-05,0.0027,0.0036,-0.12,0.21,-1.6e-06,0.43,-0.00017,0.00063,7.8e-06,0,0,-4.9e+02,0.00014,0.00014,0.037,0.02,0.022,0.021,0.042,0.042,0.05,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0096,0.0018,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16690000,0.71,0.00049,-0.013,0.71,0.0075,0.0062,-0.019,0,0,-4.9e+02,-0.0012,-0.0058,-7.9e-05,0.0022,0.0042,-0.12,0.21,-1.7e-06,0.43,-0.00018,0.00062,-3.3e-06,0,0,-4.9e+02,0.00014,0.00014,0.037,0.021,0.024,0.021,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0017,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16790000,0.71,0.00048,-0.013,0.71,0.0056,0.0068,-0.018,0,0,-4.9e+02,-0.0012,-0.0058,-8e-05,0.002,0.0039,-0.12,0.21,-1.7e-06,0.43,-0.00016,0.00063,-1.6e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.019,0.021,0.02,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0093,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16890000,0.71,0.00054,-0.013,0.71,0.0053,0.0078,-0.016,0,0,-4.9e+02,-0.0012,-0.0058,-8.2e-05,0.0023,0.0045,-0.13,0.21,-2e-06,0.43,-0.00017,0.00062,-1.2e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.02,0.023,0.02,0.046,0.047,0.05,1.6e-06,2.8e-06,2.3e-06,0.007,0.0092,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -16990000,0.71,0.00051,-0.013,0.71,0.0054,0.0055,-0.015,0,0,-4.9e+02,-0.0012,-0.0059,-8.2e-05,0.0022,0.0056,-0.13,0.21,-2.4e-06,0.43,-0.00019,0.00061,-2.2e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.018,0.021,0.019,0.041,0.042,0.049,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17090000,0.71,0.00055,-0.013,0.71,0.0057,0.007,-0.015,0,0,-4.9e+02,-0.0012,-0.0059,-8.1e-05,0.0032,0.0059,-0.13,0.21,-2.7e-06,0.43,-0.0002,0.00061,-1e-05,0,0,-4.9e+02,0.00014,0.00013,0.037,0.02,0.022,0.019,0.046,0.047,0.049,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17190000,0.71,0.00061,-0.013,0.71,0.0058,0.0079,-0.016,0,0,-4.9e+02,-0.0012,-0.0059,-7.7e-05,0.0039,0.0058,-0.13,0.21,-3e-06,0.43,-0.0002,0.00062,-7.8e-06,0,0,-4.9e+02,0.00013,0.00013,0.037,0.018,0.02,0.018,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0068,0.0088,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17290000,0.71,0.00063,-0.013,0.71,0.0076,0.0087,-0.011,0,0,-4.9e+02,-0.0012,-0.0059,-7.9e-05,0.0043,0.0068,-0.13,0.21,-3.4e-06,0.43,-0.00022,0.00061,-5.2e-06,0,0,-4.9e+02,0.00013,0.00013,0.037,0.019,0.022,0.018,0.045,0.046,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0087,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17390000,0.71,0.00068,-0.013,0.71,0.0074,0.0091,-0.0095,0,0,-4.9e+02,-0.0012,-0.0059,-7.3e-05,0.0051,0.0065,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.017,0.02,0.017,0.041,0.041,0.048,1.4e-06,2.5e-06,2.2e-06,0.0066,0.0085,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17490000,0.71,0.00063,-0.013,0.71,0.009,0.0093,-0.0078,0,0,-4.9e+02,-0.0012,-0.0059,-7.4e-05,0.0045,0.0063,-0.13,0.21,-3.3e-06,0.43,-0.00023,0.00061,7.8e-06,0,0,-4.9e+02,0.00013,0.00012,0.037,0.019,0.021,0.017,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17590000,0.71,0.0006,-0.013,0.71,0.0098,0.0084,-0.0024,0,0,-4.9e+02,-0.0012,-0.0059,-7e-05,0.0048,0.0065,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,5.1e-06,0,0,-4.9e+02,0.00013,0.00012,0.037,0.017,0.019,0.017,0.04,0.041,0.048,1.4e-06,2.3e-06,2.2e-06,0.0065,0.0083,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17690000,0.71,0.00057,-0.013,0.71,0.011,0.01,-0.003,0,0,-4.9e+02,-0.0012,-0.0059,-6.9e-05,0.0049,0.0063,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.045,0.046,0.048,1.3e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17790000,0.71,0.00056,-0.013,0.71,0.012,0.011,-0.0042,0,0,-4.9e+02,-0.0012,-0.0058,-6e-05,0.0059,0.0052,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00064,2.3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.0081,0.001,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17890000,0.71,0.00055,-0.013,0.71,0.015,0.012,-0.0041,0,0,-4.9e+02,-0.0012,-0.0058,-5.8e-05,0.0057,0.0046,-0.13,0.21,-3.2e-06,0.43,-0.00023,0.00064,2.8e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.044,0.045,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.00097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17990000,0.71,0.00049,-0.013,0.71,0.016,0.009,-0.0027,0,0,-4.9e+02,-0.0012,-0.0058,-5.7e-05,0.0054,0.0049,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00064,2.5e-05,0,0,-4.9e+02,0.00012,0.00012,0.037,0.016,0.019,0.015,0.04,0.041,0.046,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0079,0.00092,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -18090000,0.71,0.00047,-0.013,0.71,0.017,0.0082,-0.00045,0,0,-4.9e+02,-0.0012,-0.0059,-6.2e-05,0.0049,0.0058,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00061,1.9e-05,0,0,-4.9e+02,0.00012,0.00012,0.037,0.017,0.02,0.015,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00089,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18190000,0.71,0.00043,-0.013,0.71,0.017,0.0092,0.001,0,0,-4.9e+02,-0.0012,-0.0059,-5.8e-05,0.0051,0.0055,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00062,2e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.018,0.014,0.04,0.041,0.046,1.2e-06,2e-06,2.2e-06,0.0061,0.0077,0.00085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18290000,0.71,0.00035,-0.013,0.71,0.018,0.0088,0.0022,0,0,-4.9e+02,-0.0012,-0.0059,-6e-05,0.0047,0.0058,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00061,1.4e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.017,0.02,0.014,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00082,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18390000,0.71,0.00031,-0.013,0.71,0.02,0.011,0.0035,0,0,-4.9e+02,-0.0012,-0.0059,-5.4e-05,0.0044,0.005,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00062,1.6e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.045,1.1e-06,1.9e-06,2.2e-06,0.006,0.0075,0.00078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18490000,0.71,0.00038,-0.013,0.71,0.021,0.012,0.0031,0,0,-4.9e+02,-0.0012,-0.0059,-5.3e-05,0.005,0.0051,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00063,2e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.02,0.014,0.043,0.045,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18590000,0.71,0.00039,-0.013,0.71,0.02,0.013,0.0014,0,0,-4.9e+02,-0.0012,-0.0058,-4.5e-05,0.0058,0.0046,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00065,2.5e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0073,0.00072,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18690000,0.71,0.00031,-0.013,0.71,0.022,0.012,-0.00039,0,0,-4.9e+02,-0.0012,-0.0059,-4.7e-05,0.0051,0.0046,-0.13,0.21,-3.5e-06,0.43,-0.00024,0.00064,1.9e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1e-06,1.8e-06,2.2e-06,0.0058,0.0072,0.0007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18790000,0.71,0.00032,-0.013,0.71,0.021,0.012,-0.00061,0,0,-4.9e+02,-0.0012,-0.0059,-4.6e-05,0.0053,0.0052,-0.13,0.21,-3.8e-06,0.43,-0.00025,0.00063,1.6e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00067,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18890000,0.71,0.00041,-0.013,0.71,0.021,0.014,1.9e-05,0,0,-4.9e+02,-0.0012,-0.0058,-4e-05,0.0062,0.0046,-0.13,0.21,-3.8e-06,0.43,-0.00026,0.00065,2.9e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -18990000,0.71,0.00046,-0.013,0.71,0.021,0.015,-0.0012,0,0,-4.9e+02,-0.0013,-0.0058,-3.4e-05,0.0069,0.0048,-0.13,0.21,-4.1e-06,0.43,-0.00027,0.00066,3e-05,0,0,-4.9e+02,0.00011,0.0001,0.037,0.015,0.017,0.012,0.039,0.04,0.044,9.7e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00062,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19090000,0.71,0.00051,-0.013,0.71,0.021,0.016,0.0018,0,0,-4.9e+02,-0.0013,-0.0058,-3.4e-05,0.0075,0.0051,-0.13,0.21,-4.4e-06,0.43,-0.00028,0.00066,3.4e-05,0,0,-4.9e+02,0.00011,0.0001,0.037,0.016,0.019,0.012,0.042,0.044,0.044,9.6e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.0006,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19190000,0.71,0.00055,-0.013,0.71,0.02,0.016,0.0019,0,0,-4.9e+02,-0.0013,-0.0059,-2.7e-05,0.008,0.0053,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00067,3.8e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.043,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.00058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19290000,0.71,0.00058,-0.013,0.71,0.02,0.015,0.0046,0,0,-4.9e+02,-0.0013,-0.0059,-3.1e-05,0.0078,0.0057,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00066,4e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.015,0.019,0.012,0.042,0.044,0.043,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19390000,0.71,0.00054,-0.013,0.71,0.019,0.014,0.0084,0,0,-4.9e+02,-0.0013,-0.0059,-2.4e-05,0.0078,0.0055,-0.13,0.21,-4.7e-06,0.43,-0.00029,0.00065,3.6e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.014,0.017,0.011,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0055,0.0066,0.00054,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19490000,0.71,0.00055,-0.013,0.71,0.019,0.015,0.0049,0,0,-4.9e+02,-0.0013,-0.0058,-1.9e-05,0.0078,0.0048,-0.13,0.21,-4.5e-06,0.43,-0.00029,0.00066,3.9e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.015,0.018,0.011,0.042,0.044,0.043,8.8e-07,1.4e-06,2.1e-06,0.0054,0.0066,0.00052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19590000,0.71,0.00063,-0.013,0.71,0.017,0.015,0.0043,0,0,-4.9e+02,-0.0013,-0.0058,-7.4e-06,0.0086,0.0046,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00068,4.7e-05,0,0,-4.9e+02,0.00011,9.8e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.5e-07,1.4e-06,2.1e-06,0.0054,0.0065,0.0005,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19690000,0.71,0.00067,-0.013,0.71,0.017,0.013,0.0059,0,0,-4.9e+02,-0.0013,-0.0058,-1.1e-05,0.0089,0.0052,-0.13,0.21,-4.9e-06,0.43,-0.0003,0.00068,3.9e-05,0,0,-4.9e+02,0.00011,9.8e-05,0.036,0.015,0.018,0.011,0.042,0.043,0.042,8.4e-07,1.4e-06,2.1e-06,0.0053,0.0065,0.00049,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19790000,0.71,0.00074,-0.013,0.71,0.014,0.011,0.0064,0,0,-4.9e+02,-0.0013,-0.0059,-6.3e-06,0.0094,0.0055,-0.13,0.21,-5.2e-06,0.43,-0.00031,0.00068,3.8e-05,0,0,-4.9e+02,0.00011,9.6e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0064,0.00047,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19890000,0.71,0.00066,-0.013,0.71,0.015,0.013,0.0076,0,0,-4.9e+02,-0.0013,-0.0058,1.8e-06,0.0092,0.0045,-0.13,0.21,-4.9e-06,0.43,-0.0003,0.00069,4.5e-05,0,0,-4.9e+02,0.00011,9.6e-05,0.036,0.015,0.018,0.01,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19990000,0.71,0.00063,-0.013,0.7,0.013,0.013,0.01,0,0,-4.9e+02,-0.0013,-0.0058,1.7e-05,0.0095,0.0037,-0.13,0.21,-4.8e-06,0.43,-0.0003,0.0007,5.1e-05,0,0,-4.9e+02,0.0001,9.4e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.041,7.9e-07,1.3e-06,2.1e-06,0.0052,0.0062,0.00044,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -20090000,0.71,0.00066,-0.013,0.7,0.013,0.013,0.011,0,0,-4.9e+02,-0.0013,-0.0058,2.7e-05,0.01,0.0029,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00072,6.2e-05,0,0,-4.9e+02,0.00011,9.5e-05,0.036,0.014,0.018,0.01,0.041,0.043,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20190000,0.71,0.00069,-0.013,0.7,0.012,0.012,0.013,0,0,-4.9e+02,-0.0013,-0.0058,3.6e-05,0.0099,0.0026,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00072,6.1e-05,0,0,-4.9e+02,0.0001,9.3e-05,0.036,0.013,0.016,0.0098,0.038,0.039,0.041,7.6e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00042,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20290000,0.71,0.0007,-0.013,0.7,0.01,0.012,0.011,0,0,-4.9e+02,-0.0013,-0.0058,4e-05,0.01,0.0025,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00073,6.3e-05,0,0,-4.9e+02,0.0001,9.3e-05,0.036,0.014,0.018,0.0097,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.0004,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20390000,0.71,0.00065,-0.013,0.7,0.0085,0.0097,0.013,0,0,-4.9e+02,-0.0013,-0.0058,4.4e-05,0.01,0.0026,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00073,5.3e-05,0,0,-4.9e+02,0.0001,9.1e-05,0.036,0.013,0.016,0.0095,0.037,0.039,0.04,7.3e-07,1.1e-06,2e-06,0.0051,0.006,0.00039,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20490000,0.71,0.00071,-0.013,0.7,0.0086,0.0096,0.013,0,0,-4.9e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0029,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00072,5.1e-05,0,0,-4.9e+02,0.0001,9.1e-05,0.036,0.014,0.017,0.0094,0.041,0.043,0.04,7.2e-07,1.1e-06,2e-06,0.005,0.006,0.00038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20590000,0.71,0.00074,-0.013,0.7,0.0077,0.0076,0.0099,0,0,-4.9e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0035,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00072,5.1e-05,0,0,-4.9e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0092,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0059,0.00037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20690000,0.71,0.00077,-0.013,0.7,0.0084,0.0076,0.011,0,0,-4.9e+02,-0.0013,-0.0058,4.5e-05,0.01,0.0032,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00072,5.2e-05,0,0,-4.9e+02,0.0001,8.9e-05,0.036,0.014,0.017,0.0092,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.005,0.0058,0.00036,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20790000,0.71,0.0008,-0.013,0.7,0.0062,0.0071,0.012,0,0,-4.9e+02,-0.0013,-0.0058,5e-05,0.011,0.0034,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00073,4.7e-05,0,0,-4.9e+02,9.8e-05,8.8e-05,0.036,0.013,0.016,0.009,0.037,0.039,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0058,0.00035,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20890000,0.71,0.00081,-0.013,0.7,0.0061,0.0068,0.011,0,0,-4.9e+02,-0.0013,-0.0058,5.8e-05,0.011,0.003,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00074,5.2e-05,0,0,-4.9e+02,9.9e-05,8.8e-05,0.036,0.014,0.017,0.0089,0.04,0.043,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -20990000,0.71,0.00083,-0.013,0.7,0.0044,0.0045,0.011,0,0,-4.9e+02,-0.0013,-0.0058,6.2e-05,0.011,0.0032,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00074,4.9e-05,0,0,-4.9e+02,9.6e-05,8.6e-05,0.036,0.013,0.016,0.0087,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0049,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21090000,0.71,0.00081,-0.013,0.7,0.0053,0.0037,0.012,0,0,-4.9e+02,-0.0013,-0.0058,6.7e-05,0.011,0.0027,-0.13,0.21,-4.8e-06,0.43,-0.00033,0.00075,4.6e-05,0,0,-4.9e+02,9.7e-05,8.6e-05,0.036,0.014,0.017,0.0087,0.04,0.043,0.039,6.4e-07,9.9e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21190000,0.71,0.00081,-0.013,0.7,0.0056,0.0028,0.011,0,0,-4.9e+02,-0.0013,-0.0058,6.7e-05,0.011,0.0029,-0.13,0.21,-4.7e-06,0.43,-0.00032,0.00075,4.3e-05,0,0,-4.9e+02,9.5e-05,8.5e-05,0.036,0.013,0.016,0.0085,0.037,0.039,0.039,6.3e-07,9.5e-07,2e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21290000,0.71,0.0009,-0.013,0.7,0.0049,0.0029,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.8e-05,0.011,0.0025,-0.13,0.21,-4.7e-06,0.43,-0.00033,0.00077,4.7e-05,0,0,-4.9e+02,9.5e-05,8.5e-05,0.036,0.014,0.017,0.0084,0.04,0.043,0.038,6.2e-07,9.5e-07,1.9e-06,0.0048,0.0055,0.00031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21390000,0.71,0.00088,-0.013,0.7,0.0039,0.00086,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.3e-05,0.011,0.0026,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00076,4.8e-05,0,0,-4.9e+02,9.3e-05,8.3e-05,0.036,0.013,0.016,0.0083,0.037,0.039,0.038,6e-07,9.1e-07,1.9e-06,0.0047,0.0055,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21490000,0.71,0.00088,-0.013,0.7,0.0044,0.0013,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.7e-05,0.011,0.0023,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00076,5.3e-05,0,0,-4.9e+02,9.4e-05,8.4e-05,0.036,0.014,0.017,0.0082,0.04,0.043,0.038,6e-07,9.1e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21590000,0.71,0.00087,-0.013,0.7,0.0033,0.0018,0.012,0,0,-4.9e+02,-0.0013,-0.0058,7.6e-05,0.011,0.0023,-0.13,0.21,-5e-06,0.43,-0.00032,0.00076,5e-05,0,0,-4.9e+02,9.2e-05,8.2e-05,0.036,0.013,0.015,0.0081,0.037,0.039,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0054,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21690000,0.71,0.00084,-0.013,0.7,0.0049,0.0021,0.014,0,0,-4.9e+02,-0.0013,-0.0058,8e-05,0.011,0.0019,-0.13,0.21,-4.9e-06,0.43,-0.0003,0.00076,5.1e-05,0,0,-4.9e+02,9.2e-05,8.2e-05,0.036,0.013,0.017,0.0081,0.04,0.042,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0053,0.00028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21790000,0.71,0.00083,-0.013,0.7,0.003,0.0042,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.1e-05,0.011,0.0021,-0.13,0.21,-5.5e-06,0.43,-0.00032,0.00076,5.3e-05,0,0,-4.9e+02,9e-05,8.1e-05,0.036,0.012,0.015,0.0079,0.037,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0053,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21890000,0.71,0.00083,-0.013,0.7,0.0038,0.0048,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.1e-05,0.011,0.002,-0.13,0.21,-5.4e-06,0.43,-0.00032,0.00076,5.1e-05,0,0,-4.9e+02,9.1e-05,8.1e-05,0.036,0.013,0.016,0.0079,0.04,0.042,0.037,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0053,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21990000,0.71,0.00085,-0.013,0.7,0.0025,0.0054,0.014,0,0,-4.9e+02,-0.0013,-0.0058,6.9e-05,0.012,0.0019,-0.13,0.21,-5.8e-06,0.43,-0.00033,0.00076,5.2e-05,0,0,-4.9e+02,8.9e-05,7.9e-05,0.036,0.012,0.015,0.0077,0.036,0.038,0.037,5.5e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22090000,0.71,0.00087,-0.013,0.7,0.0024,0.007,0.012,0,0,-4.9e+02,-0.0013,-0.0058,6.9e-05,0.012,0.0019,-0.13,0.21,-5.8e-06,0.43,-0.00033,0.00076,5.2e-05,0,0,-4.9e+02,8.9e-05,8e-05,0.036,0.013,0.016,0.0077,0.04,0.042,0.037,5.4e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22190000,0.71,0.00084,-0.013,0.7,0.0019,0.007,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.5e-05,0.012,0.002,-0.13,0.21,-5.6e-06,0.43,-0.00034,0.00077,4.2e-05,0,0,-4.9e+02,8.7e-05,7.8e-05,0.036,0.012,0.015,0.0076,0.036,0.038,0.037,5.3e-07,7.7e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22290000,0.71,0.00087,-0.013,0.7,0.0013,0.0067,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.2e-05,0.012,0.002,-0.13,0.21,-5.6e-06,0.43,-0.00034,0.00076,4.3e-05,0,0,-4.9e+02,8.8e-05,7.8e-05,0.036,0.013,0.016,0.0075,0.04,0.042,0.037,5.2e-07,7.7e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22390000,0.71,0.00089,-0.013,0.7,-0.0011,0.0064,0.015,0,0,-4.9e+02,-0.0013,-0.0058,7.9e-05,0.012,0.0023,-0.13,0.21,-5.6e-06,0.43,-0.00034,0.00077,4.4e-05,0,0,-4.9e+02,8.6e-05,7.7e-05,0.036,0.012,0.015,0.0074,0.036,0.038,0.037,5.1e-07,7.4e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22490000,0.71,0.00093,-0.013,0.7,-0.0022,0.0073,0.016,0,0,-4.9e+02,-0.0013,-0.0058,8e-05,0.012,0.0024,-0.13,0.21,-5.5e-06,0.43,-0.00036,0.00078,4.1e-05,0,0,-4.9e+02,8.7e-05,7.7e-05,0.036,0.013,0.016,0.0074,0.039,0.042,0.037,5.1e-07,7.4e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22590000,0.71,0.00095,-0.013,0.7,-0.0038,0.0066,0.015,0,0,-4.9e+02,-0.0014,-0.0058,8.4e-05,0.013,0.0026,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00079,3.8e-05,0,0,-4.9e+02,8.5e-05,7.6e-05,0.036,0.012,0.015,0.0073,0.036,0.038,0.036,5e-07,7.1e-07,1.8e-06,0.0044,0.005,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22690000,0.71,0.001,-0.013,0.7,-0.0052,0.008,0.016,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.013,0.0025,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.0008,3.8e-05,0,0,-4.9e+02,8.5e-05,7.6e-05,0.036,0.013,0.016,0.0073,0.039,0.042,0.036,4.9e-07,7.1e-07,1.8e-06,0.0044,0.005,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22790000,0.71,0.001,-0.013,0.7,-0.0072,0.0069,0.017,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.013,0.0033,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00078,4.3e-05,0,0,-4.9e+02,8.3e-05,7.5e-05,0.036,0.012,0.015,0.0071,0.036,0.038,0.036,4.8e-07,6.8e-07,1.8e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22890000,0.71,0.00099,-0.013,0.7,-0.0076,0.0078,0.019,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.013,0.0031,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00077,3.9e-05,0,0,-4.9e+02,8.4e-05,7.5e-05,0.036,0.013,0.016,0.0071,0.039,0.042,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22990000,0.71,0.00097,-0.013,0.7,-0.0077,0.0069,0.02,0,0,-4.9e+02,-0.0014,-0.0058,8.8e-05,0.013,0.003,-0.13,0.21,-5.2e-06,0.43,-0.00037,0.00078,3.6e-05,0,0,-4.9e+02,8.2e-05,7.4e-05,0.036,0.012,0.015,0.007,0.036,0.038,0.036,4.7e-07,6.6e-07,1.7e-06,0.0044,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23090000,0.71,0.00092,-0.013,0.7,-0.0081,0.0068,0.02,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.012,0.0033,-0.13,0.21,-5.4e-06,0.43,-0.00037,0.00076,3.4e-05,0,0,-4.9e+02,8.3e-05,7.4e-05,0.036,0.013,0.016,0.007,0.039,0.042,0.036,4.7e-07,6.6e-07,1.7e-06,0.0044,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23190000,0.71,0.00097,-0.013,0.7,-0.0094,0.0048,0.022,0,0,-4.9e+02,-0.0014,-0.0058,8.2e-05,0.013,0.0035,-0.13,0.21,-5.4e-06,0.43,-0.00036,0.00076,2.6e-05,0,0,-4.9e+02,8.1e-05,7.3e-05,0.036,0.012,0.014,0.0069,0.036,0.038,0.035,4.6e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23290000,0.71,0.00089,-0.013,0.7,-0.0093,0.0042,0.022,0,0,-4.9e+02,-0.0014,-0.0058,8.4e-05,0.012,0.0033,-0.13,0.21,-5.3e-06,0.43,-0.00036,0.00076,2.5e-05,0,0,-4.9e+02,8.2e-05,7.3e-05,0.036,0.013,0.016,0.0069,0.039,0.042,0.036,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23390000,0.71,0.00095,-0.013,0.7,-0.0095,0.003,0.02,0,0,-4.9e+02,-0.0014,-0.0058,8.7e-05,0.012,0.0033,-0.13,0.21,-5.4e-06,0.43,-0.00034,0.00075,2.6e-05,0,0,-4.9e+02,8e-05,7.2e-05,0.036,0.012,0.014,0.0068,0.036,0.038,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23490000,0.71,0.0033,-0.01,0.7,-0.016,0.0033,-0.013,0,0,-4.9e+02,-0.0014,-0.0058,9.3e-05,0.012,0.0031,-0.13,0.21,-5.4e-06,0.43,-0.00033,0.00078,5.1e-05,0,0,-4.9e+02,8.1e-05,7.2e-05,0.036,0.013,0.015,0.0068,0.039,0.042,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 -23590000,0.71,0.0086,-0.0026,0.7,-0.027,0.0032,-0.045,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.012,0.0031,-0.13,0.21,-5.3e-06,0.43,-0.00033,0.00084,0.00012,0,0,-4.9e+02,7.9e-05,7.1e-05,0.036,0.012,0.014,0.0067,0.036,0.038,0.035,4.3e-07,5.9e-07,1.6e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23690000,0.71,0.0082,0.0032,0.71,-0.058,-0.0046,-0.095,0,0,-4.9e+02,-0.0014,-0.0058,9e-05,0.012,0.0031,-0.13,0.21,-5.3e-06,0.43,-0.00033,0.00078,9e-05,0,0,-4.9e+02,8e-05,7.1e-05,0.036,0.013,0.015,0.0067,0.039,0.042,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0047,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23790000,0.71,0.0052,-0.00012,0.71,-0.083,-0.016,-0.15,0,0,-4.9e+02,-0.0013,-0.0058,9.1e-05,0.011,0.0026,-0.13,0.21,-4.5e-06,0.43,-0.00038,0.00078,0.00044,0,0,-4.9e+02,7.8e-05,7e-05,0.036,0.012,0.014,0.0066,0.036,0.038,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23890000,0.71,0.0026,-0.0062,0.71,-0.1,-0.025,-0.2,0,0,-4.9e+02,-0.0013,-0.0058,9.1e-05,0.012,0.0028,-0.13,0.21,-4.4e-06,0.43,-0.00041,0.00083,0.00035,0,0,-4.9e+02,7.9e-05,7e-05,0.036,0.013,0.016,0.0066,0.039,0.042,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23990000,0.71,0.0012,-0.011,0.71,-0.1,-0.029,-0.26,0,0,-4.9e+02,-0.0013,-0.0058,9.6e-05,0.012,0.0028,-0.13,0.21,-4e-06,0.43,-0.00038,0.00083,0.00032,0,0,-4.9e+02,7.7e-05,6.9e-05,0.036,0.012,0.015,0.0065,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0046,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24090000,0.71,0.0025,-0.0095,0.71,-0.1,-0.028,-0.3,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.011,0.0025,-0.13,0.21,-3.6e-06,0.43,-0.00041,0.0008,0.00036,0,0,-4.9e+02,7.8e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0046,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24190000,0.71,0.0036,-0.0072,0.71,-0.11,-0.03,-0.35,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.011,0.0024,-0.13,0.21,-2.8e-06,0.43,-0.00041,0.00083,0.00036,0,0,-4.9e+02,7.6e-05,6.8e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,4e-07,5.4e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24290000,0.71,0.0041,-0.0064,0.71,-0.12,-0.033,-0.41,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.011,0.0023,-0.13,0.21,-2.5e-06,0.43,-0.00045,0.00088,0.00042,0,0,-4.9e+02,7.7e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4e-07,5.4e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24390000,0.71,0.0042,-0.0065,0.71,-0.13,-0.041,-0.46,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.011,0.003,-0.13,0.21,2.9e-07,0.43,-0.00033,0.00092,0.00042,0,0,-4.9e+02,7.5e-05,6.7e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24490000,0.71,0.005,-0.0024,0.71,-0.14,-0.046,-0.51,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.011,0.003,-0.13,0.21,2.9e-07,0.43,-0.00033,0.00093,0.00041,0,0,-4.9e+02,7.6e-05,6.8e-05,0.036,0.013,0.016,0.0064,0.039,0.042,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24590000,0.71,0.0055,0.0013,0.71,-0.16,-0.057,-0.56,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.003,-0.13,0.21,1.4e-06,0.43,2.7e-05,0.00058,0.00036,0,0,-4.9e+02,7.4e-05,6.7e-05,0.036,0.012,0.015,0.0063,0.036,0.038,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24690000,0.71,0.0056,0.0022,0.71,-0.18,-0.07,-0.64,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.0028,-0.13,0.21,2.4e-06,0.43,-1.8e-05,0.00062,0.00054,0,0,-4.9e+02,7.5e-05,6.7e-05,0.036,0.013,0.016,0.0063,0.039,0.042,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24790000,0.71,0.0053,0.00097,0.71,-0.2,-0.083,-0.73,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.0029,-0.13,0.21,1.8e-06,0.43,1.5e-05,0.00059,0.0003,0,0,-4.9e+02,7.3e-05,6.6e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24890000,0.71,0.0071,0.0027,0.71,-0.22,-0.094,-0.75,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.01,0.0029,-0.13,0.21,2.6e-06,0.43,-9.1e-05,0.00075,0.00032,0,0,-4.9e+02,7.4e-05,6.6e-05,0.036,0.013,0.016,0.0062,0.039,0.042,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24990000,0.71,0.0089,0.0044,0.71,-0.24,-0.1,-0.81,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.0099,0.0026,-0.13,0.21,2.1e-06,0.43,-0.00017,0.00085,-2.2e-05,0,0,-4.9e+02,7.2e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.8e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25090000,0.71,0.0092,0.0038,0.71,-0.27,-0.11,-0.86,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.0098,0.0027,-0.13,0.21,1.7e-06,0.43,-0.00019,0.00086,-5.8e-05,0,0,-4.9e+02,7.3e-05,6.5e-05,0.036,0.013,0.017,0.0062,0.039,0.042,0.033,3.7e-07,4.8e-07,1.5e-06,0.0041,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25190000,0.71,0.0087,0.0024,0.71,-0.3,-0.13,-0.91,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.0092,0.003,-0.13,0.21,7.1e-06,0.43,7e-05,0.00083,7.7e-05,0,0,-4.9e+02,7.2e-05,6.4e-05,0.035,0.012,0.016,0.0061,0.036,0.038,0.033,3.6e-07,4.6e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25290000,0.71,0.011,0.0092,0.71,-0.33,-0.14,-0.96,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.0092,0.003,-0.13,0.21,6.9e-06,0.43,9.5e-05,0.00077,8.4e-05,0,0,-4.9e+02,7.2e-05,6.5e-05,0.035,0.013,0.017,0.0061,0.039,0.042,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25390000,0.71,0.012,0.016,0.71,-0.36,-0.16,-1,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.0085,0.0027,-0.13,0.21,1.1e-05,0.43,0.0005,0.00046,0.00012,0,0,-4.9e+02,7.1e-05,6.3e-05,0.035,0.012,0.016,0.006,0.036,0.038,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25490000,0.71,0.012,0.017,0.71,-0.41,-0.18,-1.1,0,0,-4.9e+02,-0.0013,-0.0058,0.00014,0.0084,0.0026,-0.13,0.21,9.7e-06,0.43,0.00067,0.00013,0.00031,0,0,-4.9e+02,7.2e-05,6.4e-05,0.035,0.013,0.018,0.006,0.039,0.042,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25590000,0.71,0.012,0.015,0.71,-0.45,-0.21,-1.1,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.0077,0.003,-0.13,0.21,1.6e-05,0.43,0.00097,0.00014,0.00032,0,0,-4.9e+02,7.1e-05,6.3e-05,0.034,0.012,0.018,0.006,0.036,0.038,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25690000,0.71,0.015,0.022,0.71,-0.49,-0.23,-1.2,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.0077,0.003,-0.13,0.21,1.6e-05,0.43,0.00096,0.00016,0.0004,0,0,-4.9e+02,7.1e-05,6.3e-05,0.034,0.013,0.02,0.006,0.039,0.042,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0014,0.0012,0.0011,1,1,0.01 -25790000,0.71,0.018,0.028,0.71,-0.54,-0.26,-1.2,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.007,0.0023,-0.13,0.21,2e-05,0.43,0.0013,-8.6e-05,-5.5e-05,0,0,-4.9e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.0059,0.036,0.038,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 -25890000,0.71,0.018,0.029,0.71,-0.62,-0.29,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00017,0.0072,0.0022,-0.13,0.21,2.2e-05,0.43,0.0014,-1.8e-05,-0.00012,0,0,-4.9e+02,7.1e-05,6.3e-05,0.033,0.014,0.022,0.006,0.039,0.042,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 -25990000,0.7,0.017,0.025,0.71,-0.67,-0.32,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00019,0.0063,0.0026,-0.13,0.21,2.9e-05,0.43,0.0023,-0.00058,-0.00058,0,0,-4.9e+02,7e-05,6.2e-05,0.032,0.013,0.021,0.0059,0.036,0.039,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 -26090000,0.7,0.022,0.035,0.71,-0.74,-0.35,-1.3,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0064,0.0027,-0.13,0.21,2.5e-05,0.43,0.0024,-0.0005,-0.0012,0,0,-4.9e+02,7.1e-05,6.2e-05,0.032,0.014,0.024,0.0059,0.039,0.043,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 -26190000,0.7,0.024,0.045,0.71,-0.79,-0.39,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00018,0.0053,0.0016,-0.13,0.21,3.9e-05,0.43,0.0023,0.0004,-0.0014,0,0,-4.9e+02,7.1e-05,6.1e-05,0.03,0.014,0.024,0.0058,0.036,0.039,0.032,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.001,0.0013,0.001,0.001,1,1,0.01 -26290000,0.7,0.025,0.047,0.71,-0.89,-0.43,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00018,0.0053,0.0016,-0.13,0.21,3.8e-05,0.43,0.0023,0.00027,-0.0014,0,0,-4.9e+02,7.1e-05,6.2e-05,0.03,0.015,0.028,0.0059,0.039,0.043,0.033,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.00099,3.9e-05,0.00099,0.0013,0.001,0.00099,1,1,0.01 -26390000,0.7,0.024,0.044,0.71,-0.96,-0.49,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00021,0.0044,0.0024,-0.13,0.21,4.6e-05,0.44,0.0036,-0.00018,-0.0024,0,0,-4.9e+02,7.1e-05,6.1e-05,0.028,0.014,0.027,0.0058,0.036,0.039,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0042,0.00014,0.00096,3.9e-05,0.00095,0.0012,0.00096,0.00095,1,1,0.01 -26490000,0.7,0.031,0.06,0.71,-1.1,-0.53,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00021,0.0044,0.0024,-0.13,0.21,3.9e-05,0.44,0.004,-0.00099,-0.0027,0,0,-4.9e+02,7.2e-05,6.1e-05,0.028,0.016,0.031,0.0058,0.039,0.044,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0042,0.00014,0.00092,3.9e-05,0.00092,0.0012,0.00092,0.00091,1,1,0.01 -26590000,0.7,0.037,0.076,0.71,-1.2,-0.59,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00019,0.0028,0.0014,-0.13,0.21,3.9e-05,0.44,0.0042,-0.00064,-0.0048,0,0,-4.9e+02,7.2e-05,6e-05,0.025,0.015,0.031,0.0058,0.036,0.04,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0041,0.00013,0.00087,3.9e-05,0.00086,0.001,0.00087,0.00086,1,1,0.01 -26690000,0.7,0.039,0.079,0.71,-1.3,-0.65,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00019,0.0028,0.0013,-0.13,0.21,4.5e-05,0.44,0.004,-0.00013,-0.004,0,0,-4.9e+02,7.2e-05,6.1e-05,0.025,0.017,0.037,0.0058,0.04,0.045,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00081,3.9e-05,0.0008,0.001,0.00081,0.00079,1,1,0.01 -26790000,0.7,0.036,0.074,0.71,-1.4,-0.74,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00022,0.0012,0.0022,-0.13,0.21,8.4e-05,0.44,0.0055,0.00063,-0.0038,0,0,-4.9e+02,7.3e-05,6e-05,0.022,0.016,0.036,0.0057,0.036,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00076,3.9e-05,0.00075,0.00092,0.00076,0.00074,1,1,0.01 -26890000,0.7,0.045,0.096,0.71,-1.6,-0.8,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00023,0.0013,0.0021,-0.13,0.21,9e-05,0.44,0.0054,0.0013,-0.0041,0,0,-4.9e+02,7.3e-05,6e-05,0.022,0.018,0.043,0.0058,0.04,0.046,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00072,3.9e-05,0.0007,0.00092,0.00072,0.0007,1,1,0.01 -26990000,0.7,0.051,0.12,0.71,-1.7,-0.89,-1.3,0,0,-4.9e+02,-0.00099,-0.0059,0.00022,-0.00069,0.00024,-0.13,0.21,0.00013,0.44,0.0061,0.0034,-0.0056,0,0,-4.9e+02,7.4e-05,6e-05,0.019,0.017,0.042,0.0057,0.037,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00065,3.9e-05,0.00063,0.00079,0.00065,0.00062,1,1,0.01 -27090000,0.7,0.052,0.12,0.71,-1.9,-0.98,-1.3,0,0,-4.9e+02,-0.00098,-0.0059,0.00022,-0.00073,0.00025,-0.13,0.21,0.00013,0.44,0.0061,0.0035,-0.0052,0,0,-4.9e+02,7.4e-05,6e-05,0.019,0.02,0.052,0.0057,0.04,0.048,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00059,3.9e-05,0.00056,0.00078,0.0006,0.00056,1,1,0.01 -27190000,0.7,0.05,0.11,0.7,-2.1,-1,-1.2,0,0,-4.9e+02,-0.00097,-0.0059,0.00022,-0.0018,6.1e-05,-0.13,0.21,4.8e-05,0.44,0.0021,0.0027,-0.0049,0,0,-4.9e+02,7.5e-05,6e-05,0.016,0.02,0.051,0.0057,0.043,0.05,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00055,3.9e-05,0.00051,0.00066,0.00055,0.00051,1,1,0.01 -27290000,0.71,0.044,0.095,0.7,-2.3,-1.1,-1.2,0,0,-4.9e+02,-0.00097,-0.0059,0.00023,-0.0018,4.3e-05,-0.13,0.21,5.6e-05,0.44,0.002,0.0034,-0.0049,0,0,-4.9e+02,7.6e-05,6.1e-05,0.016,0.022,0.059,0.0057,0.047,0.057,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00052,3.9e-05,0.00048,0.00066,0.00052,0.00048,1,1,0.01 -27390000,0.71,0.038,0.079,0.7,-2.4,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0017,-0.13,0.21,1.3e-05,0.44,-0.00049,0.0032,-0.0064,0,0,-4.9e+02,7.6e-05,6e-05,0.013,0.021,0.052,0.0057,0.049,0.059,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00049,3.9e-05,0.00046,0.00055,0.00049,0.00046,1,1,0.01 -27490000,0.71,0.032,0.064,0.7,-2.5,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0016,-0.13,0.21,1.9e-05,0.44,-0.00057,0.0032,-0.0067,0,0,-4.9e+02,7.7e-05,6.1e-05,0.013,0.023,0.056,0.0057,0.054,0.067,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00048,3.9e-05,0.00045,0.00055,0.00048,0.00044,1,1,0.01 -27590000,0.72,0.028,0.051,0.69,-2.6,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00023,-0.0037,-0.001,-0.12,0.21,-3.7e-05,0.44,-0.0032,0.0027,-0.0066,0,0,-4.9e+02,7.7e-05,6.1e-05,0.011,0.021,0.047,0.0057,0.056,0.068,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00044,1,1,0.01 -27690000,0.72,0.027,0.05,0.69,-2.6,-1.2,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00023,-0.0036,-0.00089,-0.12,0.21,-3.3e-05,0.44,-0.0033,0.0026,-0.0068,0,0,-4.9e+02,7.8e-05,6.1e-05,0.011,0.022,0.049,0.0057,0.062,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00043,1,1,0.01 -27790000,0.72,0.027,0.051,0.69,-2.6,-1.2,-1.2,0,0,-4.9e+02,-0.00091,-0.0059,0.00022,-0.0042,-0.0007,-0.12,0.21,-6e-05,0.44,-0.005,0.0021,-0.0072,0,0,-4.9e+02,7.9e-05,6.1e-05,0.0097,0.02,0.042,0.0056,0.064,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00045,3.9e-05,0.00043,0.00041,0.00045,0.00043,1,1,0.01 -27890000,0.72,0.027,0.049,0.69,-2.7,-1.2,-1.2,0,0,-4.9e+02,-0.00091,-0.0059,0.00023,-0.0042,-0.00071,-0.12,0.21,-6.1e-05,0.44,-0.005,0.002,-0.0072,0,0,-4.9e+02,7.9e-05,6.1e-05,0.0097,0.021,0.043,0.0057,0.07,0.087,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00044,3.9e-05,0.00043,0.00041,0.00044,0.00042,1,1,0.01 -27990000,0.72,0.026,0.046,0.69,-2.7,-1.2,-1.2,0,0,-4.9e+02,-0.00093,-0.0059,0.00024,-0.004,0.00022,-0.12,0.21,-7.7e-05,0.44,-0.0064,0.0015,-0.0071,0,0,-4.9e+02,8e-05,6.1e-05,0.0087,0.02,0.038,0.0056,0.072,0.087,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00043,3.9e-05,0.00042,0.00037,0.00043,0.00042,1,1,0.01 -28090000,0.72,0.032,0.059,0.69,-2.8,-1.2,-1.2,0,0,-4.9e+02,-0.00093,-0.0059,0.00023,-0.0042,0.00043,-0.12,0.21,-7.7e-05,0.44,-0.0065,0.0014,-0.0072,0,0,-4.9e+02,8.1e-05,6.1e-05,0.0086,0.021,0.039,0.0057,0.078,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00042,3.9e-05,0.00042,0.00036,0.00042,0.00041,1,1,0.01 -28190000,0.72,0.037,0.072,0.69,-2.8,-1.2,-0.94,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0042,0.00087,-0.12,0.21,-9.5e-05,0.44,-0.0073,0.00091,-0.0071,0,0,-4.9e+02,8.1e-05,6.1e-05,0.0079,0.02,0.034,0.0056,0.08,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00041,3.9e-05,0.00041,0.00033,0.00041,0.00041,1,1,0.01 -28290000,0.72,0.029,0.055,0.69,-2.8,-1.2,-0.078,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0043,0.00098,-0.12,0.21,-9.8e-05,0.44,-0.0073,0.0013,-0.0069,0,0,-4.9e+02,8.2e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.087,0.11,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28390000,0.73,0.012,0.024,0.69,-2.8,-1.2,0.78,0,0,-4.9e+02,-0.00094,-0.0059,0.00023,-0.0042,0.0013,-0.12,0.21,-8.5e-05,0.44,-0.0075,0.0014,-0.007,0,0,-4.9e+02,8.3e-05,6.2e-05,0.0079,0.02,0.035,0.0057,0.094,0.12,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28490000,0.73,0.0028,0.006,0.69,-2.8,-1.2,1.1,0,0,-4.9e+02,-0.00095,-0.0059,0.00023,-0.0039,0.0015,-0.12,0.21,-6.7e-05,0.44,-0.0076,0.0014,-0.0069,0,0,-4.9e+02,8.4e-05,6.2e-05,0.0079,0.021,0.035,0.0057,0.1,0.13,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28590000,0.73,0.00088,0.0025,0.69,-2.7,-1.2,0.97,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0039,0.0016,-0.12,0.21,-6.9e-05,0.44,-0.0075,0.0015,-0.007,0,0,-4.9e+02,8.4e-05,6.2e-05,0.0079,0.021,0.033,0.0057,0.11,0.14,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28690000,0.73,0.00018,0.0016,0.69,-2.6,-1.2,0.98,0,0,-4.9e+02,-0.00095,-0.0059,0.00024,-0.0036,0.0019,-0.12,0.21,-5.2e-05,0.44,-0.0076,0.0014,-0.0068,0,0,-4.9e+02,8.5e-05,6.2e-05,0.0079,0.022,0.033,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.00039,0.0004,1,1,0.01 -28790000,0.73,-1.6e-05,0.0015,0.69,-2.6,-1.2,0.98,0,0,-4.9e+02,-0.00098,-0.0059,0.00024,-0.0031,0.0022,-0.12,0.21,-9.3e-05,0.44,-0.0091,0.00063,-0.006,0,0,-4.9e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 -28890000,0.73,-6.2e-06,0.0018,0.69,-2.5,-1.2,0.97,0,0,-4.9e+02,-0.00099,-0.0059,0.00024,-0.0029,0.0025,-0.12,0.21,-7.6e-05,0.44,-0.0091,0.00059,-0.0059,0,0,-4.9e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.13,0.16,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 -28990000,0.73,0.00034,0.0024,0.68,-2.5,-1.1,0.97,0,0,-4.9e+02,-0.001,-0.0059,0.00025,-0.0016,0.0029,-0.12,0.21,-0.00011,0.44,-0.011,-0.00033,-0.0047,0,0,-4.9e+02,8.7e-05,6.2e-05,0.0073,0.02,0.025,0.0056,0.13,0.16,0.032,3e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.0003,0.00039,0.00039,1,1,0.01 -29090000,0.73,0.00051,0.0028,0.68,-2.4,-1.1,0.96,0,0,-4.9e+02,-0.001,-0.0059,0.00025,-0.0014,0.0033,-0.12,0.21,-9.3e-05,0.44,-0.011,-0.00039,-0.0046,0,0,-4.9e+02,8.8e-05,6.2e-05,0.0073,0.021,0.025,0.0057,0.14,0.17,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29190000,0.73,0.00076,0.0032,0.68,-2.4,-1.1,0.95,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00098,0.0034,-0.12,0.21,-0.00013,0.44,-0.011,-0.00062,-0.0042,0,0,-4.9e+02,8.8e-05,6.1e-05,0.0072,0.02,0.023,0.0056,0.14,0.17,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29290000,0.73,0.0011,0.004,0.68,-2.3,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00095,0.0038,-0.12,0.21,-0.00012,0.44,-0.011,-0.00069,-0.0041,0,0,-4.9e+02,8.9e-05,6.2e-05,0.0072,0.021,0.024,0.0056,0.14,0.18,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29390000,0.73,0.0017,0.0055,0.68,-2.3,-1.1,0.99,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00022,0.0043,-0.12,0.21,-0.00015,0.44,-0.012,-0.0014,-0.0033,0,0,-4.9e+02,8.8e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.18,0.031,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 -29490000,0.73,0.0022,0.0066,0.68,-2.3,-1.1,0.99,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,-0.00021,0.0045,-0.12,0.21,-0.00015,0.44,-0.012,-0.0013,-0.0033,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.15,0.19,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 -29590000,0.73,0.0027,0.0076,0.68,-2.2,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.00041,0.0045,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.19,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00038,1,1,0.01 -29690000,0.73,0.003,0.0082,0.68,-2.2,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00025,0.00035,0.0049,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-4.9e+02,9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29790000,0.73,0.0034,0.0087,0.68,-2.2,-1.1,0.96,0,0,-4.9e+02,-0.0012,-0.0059,0.00025,0.0014,0.0047,-0.12,0.21,-0.00018,0.44,-0.012,-0.0019,-0.0023,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29890000,0.73,0.0034,0.0088,0.68,-2.1,-1.1,0.95,0,0,-4.9e+02,-0.0012,-0.0059,0.00024,0.0011,0.0052,-0.12,0.21,-0.00018,0.44,-0.013,-0.0019,-0.0023,0,0,-4.9e+02,9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.17,0.21,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29990000,0.73,0.0036,0.0089,0.68,-2.1,-1.1,0.94,0,0,-4.9e+02,-0.0012,-0.0059,0.00022,0.0016,0.0049,-0.12,0.21,-0.0002,0.44,-0.013,-0.0021,-0.002,0,0,-4.9e+02,8.9e-05,6e-05,0.0071,0.02,0.024,0.0056,0.17,0.21,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -30090000,0.73,0.0035,0.0088,0.68,-2.1,-1.1,0.92,0,0,-4.9e+02,-0.0012,-0.0059,0.00022,0.0013,0.0052,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.18,0.22,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -30190000,0.73,0.0036,0.0085,0.68,-2.1,-1.1,0.91,0,0,-4.9e+02,-0.0012,-0.0059,0.00021,0.0021,0.0047,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-4.9e+02,8.8e-05,6e-05,0.007,0.02,0.025,0.0056,0.18,0.22,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00037,0.00038,1,1,0.01 -30290000,0.73,0.0034,0.0083,0.68,-2,-1.1,0.9,0,0,-4.9e+02,-0.0012,-0.0059,0.00021,0.0019,0.0049,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-4.9e+02,8.9e-05,6.1e-05,0.007,0.021,0.026,0.0056,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30390000,0.73,0.0035,0.008,0.68,-2,-1.1,0.89,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0027,0.0047,-0.12,0.21,-0.00022,0.43,-0.012,-0.0025,-0.0014,0,0,-4.9e+02,8.7e-05,6e-05,0.007,0.021,0.025,0.0055,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30490000,0.73,0.0034,0.0077,0.68,-2,-1.1,0.87,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0026,0.0049,-0.12,0.21,-0.00022,0.43,-0.012,-0.0024,-0.0014,0,0,-4.9e+02,8.8e-05,6e-05,0.007,0.022,0.027,0.0056,0.2,0.24,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.8e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30590000,0.73,0.0034,0.0073,0.68,-1.9,-1,0.83,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0034,0.0045,-0.12,0.21,-0.00024,0.43,-0.012,-0.0025,-0.001,0,0,-4.9e+02,8.6e-05,6e-05,0.0069,0.021,0.026,0.0055,0.2,0.24,0.031,2.8e-07,3.5e-07,1.1e-06,0.0038,0.0039,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30690000,0.73,0.0031,0.0069,0.68,-1.9,-1,0.83,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0032,0.0048,-0.12,0.21,-0.00024,0.43,-0.012,-0.0024,-0.001,0,0,-4.9e+02,8.6e-05,6e-05,0.0069,0.022,0.028,0.0055,0.21,0.25,0.031,2.8e-07,3.5e-07,1.1e-06,0.0038,0.0039,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30790000,0.73,0.0031,0.0065,0.68,-1.9,-1,0.82,0,0,-4.9e+02,-0.0012,-0.0059,0.00014,0.004,0.0042,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00079,0,0,-4.9e+02,8.4e-05,6e-05,0.0068,0.021,0.027,0.0055,0.21,0.25,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30890000,0.73,0.0029,0.006,0.68,-1.9,-1,0.81,0,0,-4.9e+02,-0.0013,-0.0059,0.00015,0.004,0.0046,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00077,0,0,-4.9e+02,8.5e-05,6e-05,0.0068,0.022,0.029,0.0055,0.22,0.26,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30990000,0.73,0.003,0.0054,0.68,-1.8,-1,0.8,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.0049,0.004,-0.12,0.21,-0.00025,0.43,-0.011,-0.0027,-0.00043,0,0,-4.9e+02,8.3e-05,6e-05,0.0067,0.021,0.028,0.0055,0.22,0.26,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.5e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31090000,0.73,0.0027,0.0049,0.68,-1.8,-1,0.79,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.0046,0.0044,-0.12,0.21,-0.00026,0.43,-0.012,-0.0027,-0.00043,0,0,-4.9e+02,8.4e-05,6e-05,0.0067,0.022,0.03,0.0055,0.23,0.27,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31190000,0.73,0.0026,0.0044,0.68,-1.8,-1,0.78,0,0,-4.9e+02,-0.0013,-0.0058,9.6e-05,0.0049,0.0044,-0.12,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00026,0,0,-4.9e+02,8.1e-05,5.9e-05,0.0066,0.021,0.028,0.0055,0.23,0.27,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31290000,0.73,0.0023,0.0039,0.68,-1.8,-1,0.78,0,0,-4.9e+02,-0.0013,-0.0058,9.9e-05,0.0047,0.0048,-0.11,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00029,0,0,-4.9e+02,8.2e-05,6e-05,0.0066,0.022,0.03,0.0055,0.24,0.28,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.3e-05,0.00036,3.8e-05,0.00038,0.00027,0.00035,0.00037,1,1,0.01 -31390000,0.73,0.0022,0.0032,0.68,-1.7,-0.99,0.78,0,0,-4.9e+02,-0.0013,-0.0058,7.7e-05,0.0051,0.0045,-0.11,0.21,-0.0003,0.43,-0.011,-0.0028,-3.3e-05,0,0,-4.9e+02,7.9e-05,5.9e-05,0.0065,0.021,0.029,0.0054,0.24,0.28,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 -31490000,0.73,0.0019,0.0026,0.68,-1.7,-0.99,0.78,0,0,-4.9e+02,-0.0013,-0.0058,7.3e-05,0.005,0.0051,-0.11,0.21,-0.0003,0.43,-0.011,-0.0029,3.9e-06,0,0,-4.9e+02,8e-05,5.9e-05,0.0065,0.022,0.031,0.0055,0.25,0.29,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 -31590000,0.73,0.002,0.0021,0.68,-1.7,-0.97,0.77,0,0,-4.9e+02,-0.0013,-0.0058,4.6e-05,0.0059,0.0047,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00024,0,0,-4.9e+02,7.8e-05,5.9e-05,0.0063,0.021,0.029,0.0054,0.25,0.29,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31690000,0.73,0.0016,0.0013,0.68,-1.6,-0.97,0.78,0,0,-4.9e+02,-0.0013,-0.0058,4.8e-05,0.0056,0.0051,-0.11,0.21,-0.0003,0.43,-0.01,-0.0029,0.00021,0,0,-4.9e+02,7.8e-05,5.9e-05,0.0063,0.022,0.031,0.0054,0.26,0.3,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31790000,0.73,0.0015,0.00056,0.69,-1.6,-0.95,0.78,0,0,-4.9e+02,-0.0013,-0.0058,2.3e-05,0.0067,0.0049,-0.11,0.21,-0.0003,0.43,-0.0097,-0.0029,0.00055,0,0,-4.9e+02,7.6e-05,5.9e-05,0.0062,0.021,0.029,0.0054,0.26,0.3,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31890000,0.73,0.0013,-0.00017,0.69,-1.6,-0.95,0.77,0,0,-4.9e+02,-0.0013,-0.0058,2.3e-05,0.0066,0.0054,-0.11,0.21,-0.00029,0.43,-0.0097,-0.0029,0.00058,0,0,-4.9e+02,7.7e-05,5.9e-05,0.0062,0.022,0.031,0.0054,0.27,0.31,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31990000,0.73,0.0012,-0.00078,0.69,-1.6,-0.93,0.77,0,0,-4.9e+02,-0.0013,-0.0058,-8e-06,0.0071,0.0053,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00075,0,0,-4.9e+02,7.4e-05,5.8e-05,0.006,0.021,0.03,0.0054,0.27,0.31,0.031,2.6e-07,2.9e-07,9.8e-07,0.0037,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32090000,0.73,0.00083,-0.0015,0.69,-1.5,-0.93,0.78,0,0,-4.9e+02,-0.0013,-0.0058,-8.9e-06,0.0069,0.0058,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00076,0,0,-4.9e+02,7.5e-05,5.9e-05,0.006,0.022,0.032,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.8e-07,0.0037,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32190000,0.73,0.00062,-0.0025,0.69,-1.5,-0.91,0.78,0,0,-4.9e+02,-0.0014,-0.0058,-4.3e-05,0.0074,0.0058,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-4.9e+02,7.3e-05,5.8e-05,0.0059,0.021,0.03,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.6e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32290000,0.73,0.00035,-0.0032,0.69,-1.5,-0.91,0.77,0,0,-4.9e+02,-0.0014,-0.0058,-4.3e-05,0.0072,0.0064,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-4.9e+02,7.3e-05,5.8e-05,0.0059,0.022,0.032,0.0054,0.29,0.33,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32390000,0.73,0.00025,-0.004,0.69,-1.5,-0.89,0.77,0,0,-4.9e+02,-0.0014,-0.0058,-6.1e-05,0.0077,0.0063,-0.11,0.2,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-4.9e+02,7.1e-05,5.8e-05,0.0057,0.021,0.03,0.0054,0.29,0.33,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32490000,0.72,0.0001,-0.0042,0.69,-1.4,-0.88,0.78,0,0,-4.9e+02,-0.0014,-0.0058,-5.9e-05,0.0075,0.0067,-0.11,0.2,-0.0003,0.43,-0.0084,-0.0031,0.0011,0,0,-4.9e+02,7.2e-05,5.8e-05,0.0057,0.022,0.032,0.0054,0.3,0.34,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32590000,0.72,0.00015,-0.0046,0.69,-1.4,-0.87,0.78,0,0,-4.9e+02,-0.0014,-0.0057,-8e-05,0.0079,0.0067,-0.11,0.21,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-4.9e+02,7e-05,5.8e-05,0.0056,0.021,0.03,0.0053,0.3,0.34,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32690000,0.72,0.00011,-0.0046,0.69,-1.4,-0.86,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-8.1e-05,0.0079,0.0071,-0.11,0.2,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-4.9e+02,7e-05,5.8e-05,0.0056,0.022,0.032,0.0053,0.31,0.35,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00036,1,1,0.01 -32790000,0.72,0.00023,-0.0047,0.69,-1.3,-0.84,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.0001,0.0082,0.0071,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0031,0.0015,0,0,-4.9e+02,6.8e-05,5.7e-05,0.0054,0.022,0.03,0.0053,0.3,0.35,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -32890000,0.72,0.00031,-0.0046,0.69,-1.3,-0.84,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.0081,0.0077,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0032,0.0016,0,0,-4.9e+02,6.9e-05,5.8e-05,0.0054,0.022,0.031,0.0053,0.32,0.36,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -32990000,0.72,0.00052,-0.0047,0.69,-1.3,-0.82,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.0086,0.0078,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-4.9e+02,6.7e-05,5.7e-05,0.0052,0.021,0.029,0.0053,0.31,0.36,0.03,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -33090000,0.72,0.00049,-0.0048,0.69,-1.3,-0.82,0.76,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.0085,0.0081,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-4.9e+02,6.8e-05,5.7e-05,0.0053,0.022,0.031,0.0053,0.33,0.37,0.031,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -33190000,0.72,0.0039,-0.0039,0.7,-1.2,-0.8,0.7,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.0086,0.008,-0.11,0.21,-0.0003,0.43,-0.0068,-0.0031,0.0017,0,0,-4.9e+02,6.6e-05,5.7e-05,0.0051,0.022,0.029,0.0053,0.32,0.37,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 -33290000,0.67,0.016,-0.0033,0.74,-1.2,-0.78,0.68,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.0084,0.0083,-0.11,0.2,-0.00028,0.43,-0.007,-0.0032,0.0016,0,0,-4.9e+02,6.6e-05,5.7e-05,0.0051,0.022,0.031,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0036,8.3e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 -33390000,0.56,0.014,-0.0037,0.83,-1.2,-0.77,0.88,0,0,-4.9e+02,-0.0014,-0.0057,-0.00013,0.0086,0.0086,-0.11,0.21,-0.00034,0.43,-0.0063,-0.0032,0.0018,0,0,-4.9e+02,6.5e-05,5.6e-05,0.0047,0.021,0.028,0.0053,0.33,0.38,0.031,2.4e-07,2.6e-07,8.3e-07,0.0036,0.0035,8.3e-05,0.00032,3.8e-05,0.00036,0.00021,0.00032,0.00036,1,1,0.01 -33490000,0.43,0.007,-0.0011,0.9,-1.2,-0.76,0.89,0,0,-4.9e+02,-0.0014,-0.0057,-0.00015,0.0086,0.0087,-0.11,0.21,-0.00043,0.43,-0.0058,-0.002,0.0018,0,0,-4.9e+02,6.5e-05,5.6e-05,0.0041,0.022,0.029,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.1e-07,0.0036,0.0035,8.3e-05,0.00025,3.7e-05,0.00036,0.00017,0.00024,0.00036,1,1,0.01 -33590000,0.27,0.00094,-0.0036,0.96,-1.2,-0.75,0.86,0,0,-4.9e+02,-0.0014,-0.0057,-0.00018,0.0086,0.0087,-0.11,0.21,-0.00067,0.43,-0.0038,-0.0013,0.002,0,0,-4.9e+02,6.4e-05,5.5e-05,0.0031,0.02,0.027,0.0052,0.34,0.37,0.03,2.4e-07,2.6e-07,7.9e-07,0.0036,0.0035,8.3e-05,0.00016,3.6e-05,0.00036,0.00012,0.00015,0.00036,1,1,0.01 -33690000,0.098,-0.0027,-0.0066,1,-1.1,-0.74,0.87,0,0,-4.9e+02,-0.0014,-0.0057,-0.00019,0.0086,0.0087,-0.11,0.21,-0.00072,0.43,-0.0035,-0.001,0.002,0,0,-4.9e+02,6.4e-05,5.5e-05,0.0024,0.021,0.028,0.0053,0.35,0.37,0.031,2.4e-07,2.6e-07,7.8e-07,0.0036,0.0035,8.3e-05,0.0001,3.5e-05,0.00036,8.3e-05,9.8e-05,0.00036,1,1,0.01 -33790000,-0.074,-0.0045,-0.0084,1,-1.1,-0.72,0.85,0,0,-4.9e+02,-0.0014,-0.0057,-0.00021,0.0086,0.0087,-0.11,0.21,-0.00088,0.43,-0.0021,-0.001,0.0023,0,0,-4.9e+02,6.2e-05,5.4e-05,0.0019,0.02,0.026,0.0052,0.35,0.37,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,6.8e-05,3.5e-05,0.00036,5.5e-05,6.1e-05,0.00036,1,1,0.01 -33890000,-0.24,-0.0059,-0.009,0.97,-1,-0.69,0.83,0,0,-4.9e+02,-0.0014,-0.0057,-0.00022,0.0086,0.0087,-0.11,0.21,-0.001,0.43,-0.0012,-0.0011,0.0024,0,0,-4.9e+02,6.2e-05,5.4e-05,0.0016,0.022,0.028,0.0052,0.36,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,4.8e-05,3.4e-05,0.00036,3.8e-05,4.1e-05,0.00036,1,1,0.01 -33990000,-0.39,-0.0046,-0.012,0.92,-0.94,-0.64,0.8,0,0,-4.9e+02,-0.0015,-0.0057,-0.00022,0.0086,0.0088,-0.11,0.21,-0.00098,0.43,-0.0011,-0.00064,0.0025,0,0,-4.9e+02,6e-05,5.3e-05,0.0015,0.021,0.027,0.0052,0.36,0.37,0.03,2.4e-07,2.5e-07,7.7e-07,0.0036,0.0035,8.3e-05,3.6e-05,3.4e-05,0.00036,2.8e-05,2.9e-05,0.00036,1,1,0.01 -34090000,-0.5,-0.0037,-0.014,0.87,-0.88,-0.59,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00022,0.0086,0.0091,-0.11,0.21,-0.00095,0.43,-0.0012,-0.00052,0.0025,0,0,-4.9e+02,6e-05,5.3e-05,0.0014,0.023,0.03,0.0052,0.37,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,3e-05,3.4e-05,0.00036,2.2e-05,2.3e-05,0.00036,1,1,0.01 -34190000,-0.57,-0.0037,-0.012,0.82,-0.85,-0.54,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00021,0.0064,0.012,-0.11,0.21,-0.00094,0.43,-0.001,-0.00031,0.0027,0,0,-4.9e+02,5.7e-05,5.1e-05,0.0013,0.023,0.029,0.0052,0.37,0.38,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.5e-05,3.4e-05,0.00036,1.8e-05,1.8e-05,0.00036,1,1,0.01 -34290000,-0.61,-0.0046,-0.0091,0.79,-0.8,-0.48,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00021,0.0062,0.012,-0.11,0.21,-0.00096,0.43,-0.00092,-0.00018,0.0027,0,0,-4.9e+02,5.7e-05,5.1e-05,0.0012,0.025,0.032,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.2e-05,3.4e-05,0.00036,1.5e-05,1.5e-05,0.00036,1,1,0.01 -34390000,-0.63,-0.0052,-0.0062,0.77,-0.77,-0.44,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00019,0.0034,0.016,-0.11,0.21,-0.00092,0.43,-0.00091,1.7e-05,0.0029,0,0,-4.9e+02,5.4e-05,4.9e-05,0.0012,0.025,0.031,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,2e-05,3.3e-05,0.00036,1.3e-05,1.3e-05,0.00036,1,1,0.01 -34490000,-0.65,-0.0062,-0.004,0.76,-0.72,-0.39,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00019,0.0032,0.016,-0.11,0.21,-0.00093,0.43,-0.00085,-2.4e-05,0.0029,0,0,-4.9e+02,5.4e-05,4.9e-05,0.0011,0.027,0.035,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.6e-07,0.0034,0.0035,8.1e-05,1.8e-05,3.3e-05,0.00036,1.2e-05,1.2e-05,0.00036,1,1,0.01 -34590000,-0.66,-0.0062,-0.0026,0.75,-0.7,-0.37,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,-0.0018,0.023,-0.11,0.21,-0.00088,0.43,-0.00092,3.1e-05,0.0032,0,0,-4.9e+02,5e-05,4.7e-05,0.0011,0.027,0.034,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,1.1e-05,1e-05,0.00036,1,1,0.01 -34690000,-0.67,-0.0066,-0.0018,0.75,-0.64,-0.32,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,-0.002,0.023,-0.11,0.21,-0.00091,0.43,-0.00078,0.00023,0.0031,0,0,-4.9e+02,5e-05,4.7e-05,0.0011,0.03,0.037,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,9.9e-06,9.4e-06,0.00036,1,1,0.01 -34790000,-0.67,-0.006,-0.0013,0.74,-0.63,-0.3,0.79,0,0,-4.9e+02,-0.0015,-0.0058,-0.00011,-0.008,0.03,-0.11,0.21,-0.0009,0.43,-0.00062,0.00032,0.0032,0,0,-4.9e+02,4.6e-05,4.4e-05,0.001,0.029,0.036,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,9.1e-06,8.6e-06,0.00036,1,1,0.01 -34890000,-0.67,-0.006,-0.0012,0.74,-0.57,-0.26,0.79,0,0,-4.9e+02,-0.0015,-0.0058,-0.00011,-0.0081,0.03,-0.11,0.21,-0.00089,0.43,-0.00063,0.00028,0.0033,0,0,-4.9e+02,4.6e-05,4.4e-05,0.001,0.032,0.04,0.0052,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,8.4e-06,7.9e-06,0.00036,1,1,0.01 -34990000,-0.67,-0.013,-0.0037,0.74,0.47,0.35,-0.043,0,0,-4.9e+02,-0.0016,-0.0058,-6.8e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00051,0.00034,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.001,0.034,0.046,0.0054,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.3e-05,3.3e-05,0.00036,8e-06,7.4e-06,0.00036,1,1,0.01 -35090000,-0.67,-0.013,-0.0037,0.74,0.6,0.39,-0.1,0,0,-4.9e+02,-0.0016,-0.0058,-6.9e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00047,0.00028,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00099,0.037,0.051,0.0055,0.42,0.43,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.2e-05,3.3e-05,0.00036,7.5e-06,6.9e-06,0.00036,1,1,0.01 -35190000,-0.67,-0.013,-0.0038,0.74,0.63,0.43,-0.1,0,0,-4.9e+02,-0.0016,-0.0058,-7e-05,-0.016,0.039,-0.11,0.21,-0.00088,0.43,-0.00041,0.00032,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00099,0.041,0.055,0.0055,0.43,0.44,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.2e-05,3.3e-05,0.00036,7.1e-06,6.4e-06,0.00036,1,1,0.01 -35290000,-0.67,-0.013,-0.0038,0.74,0.66,0.47,-0.099,0,0,-4.9e+02,-0.0016,-0.0058,-7.1e-05,-0.016,0.039,-0.11,0.21,-0.00089,0.43,-0.00033,0.00032,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00098,0.044,0.06,0.0055,0.44,0.45,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.8e-06,6.1e-06,0.00036,1,1,0.01 -35390000,-0.67,-0.013,-0.0038,0.74,0.69,0.51,-0.096,0,0,-4.9e+02,-0.0016,-0.0058,-7.4e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00023,0.0003,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00098,0.048,0.064,0.0055,0.46,0.47,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.5e-06,5.8e-06,0.00036,1,1,0.01 -35490000,-0.67,-0.013,-0.0038,0.74,0.73,0.56,-0.095,0,0,-4.9e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00014,0.00025,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00097,0.053,0.069,0.0055,0.47,0.48,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.2e-06,5.5e-06,0.00036,1,1,0.01 -35590000,-0.67,-0.013,-0.0038,0.74,0.76,0.6,-0.094,0,0,-4.9e+02,-0.0016,-0.0058,-7.5e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00017,0.00025,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00097,0.057,0.075,0.0055,0.49,0.5,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6e-06,5.2e-06,0.00036,1,1,0.01 -35690000,-0.67,-0.013,-0.0038,0.74,0.79,0.64,-0.092,0,0,-4.9e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-9.2e-05,0.00024,0.0036,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.062,0.08,0.0056,0.51,0.52,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0032,8e-05,1e-05,3.3e-05,0.00036,5.8e-06,5e-06,0.00036,1,1,0.01 -35790000,-0.67,-0.013,-0.0038,0.74,0.82,0.68,-0.089,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-6.8e-05,0.00024,0.0036,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.067,0.086,0.0056,0.53,0.54,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0032,8e-05,1e-05,3.3e-05,0.00036,5.6e-06,4.8e-06,0.00036,1,1,0.023 -35890000,-0.67,-0.013,-0.0039,0.74,0.85,0.72,-0.086,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00094,0.43,-5.3e-05,0.00022,0.0037,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.072,0.092,0.0056,0.55,0.56,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.4e-06,4.6e-06,0.00036,1,1,0.048 -35990000,-0.67,-0.013,-0.0038,0.74,0.88,0.76,-0.083,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-7.8e-05,0.00021,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.078,0.099,0.0056,0.57,0.59,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.9e-06,3.3e-05,0.00036,5.3e-06,4.5e-06,0.00036,1,1,0.073 -36090000,-0.68,-0.013,-0.0038,0.74,0.91,0.81,-0.079,0,0,-4.9e+02,-0.0016,-0.0058,-7.9e-05,-0.016,0.039,-0.11,0.21,-0.00094,0.43,-4.3e-05,0.00019,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.083,0.11,0.0056,0.6,0.62,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.7e-06,3.3e-05,0.00036,5.2e-06,4.3e-06,0.00036,1,1,0.099 -36190000,-0.68,-0.013,-0.0038,0.74,0.94,0.85,-0.075,0,0,-4.9e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,5.5e-05,0.00018,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.089,0.11,0.0056,0.63,0.65,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.5e-06,3.3e-05,0.00036,5e-06,4.2e-06,0.00036,1,1,0.12 -36290000,-0.68,-0.013,-0.0038,0.74,0.97,0.89,-0.07,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.016,0.039,-0.11,0.21,-0.00096,0.43,7.5e-05,0.00018,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.096,0.12,0.0056,0.66,0.68,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.4e-06,3.3e-05,0.00036,4.9e-06,4.1e-06,0.00036,1,1,0.15 -36390000,-0.68,-0.013,-0.0038,0.74,1,0.93,-0.067,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.016,0.039,-0.11,0.21,-0.00096,0.43,7.2e-05,0.00022,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.1,0.13,0.0056,0.69,0.72,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.3e-06,3.3e-05,0.00036,4.8e-06,3.9e-06,0.00036,1,1,0.17 -36490000,-0.68,-0.013,-0.0038,0.74,1,0.97,-0.063,0,0,-4.9e+02,-0.0016,-0.0058,-8.3e-05,-0.015,0.039,-0.11,0.21,-0.00095,0.43,4.2e-05,0.00023,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.11,0.13,0.0056,0.72,0.76,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.2e-06,3.3e-05,0.00036,4.7e-06,3.8e-06,0.00036,1,1,0.2 -36590000,-0.68,-0.013,-0.0038,0.74,1.1,1,-0.057,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,9e-05,0.00025,0.0037,0,0,-4.9e+02,4.3e-05,4.3e-05,0.00096,0.12,0.14,0.0056,0.76,0.8,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.1e-06,3.3e-05,0.00036,4.6e-06,3.7e-06,0.00036,1,1,0.23 -36690000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.053,0,0,-4.9e+02,-0.0016,-0.0058,-8.8e-05,-0.015,0.039,-0.11,0.21,-0.00097,0.43,0.00012,0.00027,0.0037,0,0,-4.9e+02,4.3e-05,4.3e-05,0.00096,0.12,0.15,0.0057,0.8,0.85,0.032,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9e-06,3.3e-05,0.00036,4.6e-06,3.6e-06,0.00036,1,1,0.25 -36790000,-0.68,-0.013,-0.0037,0.74,1.1,1.1,-0.047,0,0,-4.9e+02,-0.0016,-0.0058,-9.1e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00017,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.13,0.16,0.0057,0.84,0.9,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.9e-06,3.3e-05,0.00036,4.5e-06,3.5e-06,0.00036,1,1,0.28 -36890000,-0.68,-0.013,-0.0037,0.74,1.2,1.1,-0.042,0,0,-4.9e+02,-0.0016,-0.0058,-9.4e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00021,0.00022,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.14,0.17,0.0056,0.89,0.95,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.8e-06,3.3e-05,0.00036,4.4e-06,3.4e-06,0.00036,1,1,0.3 -36990000,-0.68,-0.013,-0.0037,0.74,1.2,1.2,-0.037,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00023,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,0.94,1,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.7e-06,3.3e-05,0.00036,4.3e-06,3.4e-06,0.00036,1,1,0.33 -37090000,-0.68,-0.013,-0.0036,0.74,1.2,1.2,-0.031,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00023,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,1,1.1,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.7e-05,8.6e-06,3.3e-05,0.00036,4.3e-06,3.3e-06,0.00036,1,1,0.35 -37190000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.025,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00023,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.16,0.19,0.0057,1.1,1.1,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.6e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00036,1,1,0.38 -37290000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.02,0,0,-4.9e+02,-0.0016,-0.0058,-9.8e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00024,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.4e-05,0.00096,0.17,0.2,0.0057,1.1,1.2,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.41 -37390000,-0.68,-0.013,-0.0036,0.74,1.3,1.4,-0.015,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00027,0.00027,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.18,0.21,0.0057,1.2,1.3,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3.1e-06,0.00035,1,1,0.43 -37490000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0093,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.001,0.43,0.0003,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.19,0.22,0.0057,1.3,1.4,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3e-06,0.00035,1,1,0.46 -37590000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0027,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00032,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.2,0.23,0.0057,1.3,1.5,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.3e-06,3.3e-05,0.00036,4e-06,3e-06,0.00035,1,1,0.48 -37690000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,0.0046,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00033,0.00029,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.21,0.24,0.0057,1.4,1.6,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.51 -37790000,-0.68,-0.013,-0.0036,0.74,1.5,1.5,0.012,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00034,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.22,0.26,0.0056,1.5,1.7,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.54 -37890000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.017,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-4.9e+02,4.5e-05,4.5e-05,0.00096,0.23,0.27,0.0056,1.6,1.8,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.56 -37990000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.025,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.24,0.28,0.0056,1.7,1.9,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.59 -38090000,-0.68,-0.013,-0.0036,0.74,1.5,1.7,0.034,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00037,0.0003,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.25,0.29,0.0056,1.8,2,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.61 -38190000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.04,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.26,0.3,0.0056,1.9,2.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.64 -38290000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.046,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00028,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.27,0.31,0.0056,2.1,2.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.67 -38390000,-0.68,-0.013,-0.0035,0.74,1.6,1.8,0.052,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.036,-0.11,0.21,-0.001,0.43,0.00037,0.00029,0.0037,0,0,-4.9e+02,4.6e-05,4.6e-05,0.00096,0.28,0.33,0.0056,2.2,2.5,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.69 -38490000,-0.68,-0.013,-0.0035,0.74,1.7,1.8,0.058,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.036,-0.11,0.21,-0.001,0.43,0.00038,0.00031,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.29,0.34,0.0056,2.3,2.6,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.72 -38590000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.063,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00032,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.3,0.35,0.0056,2.5,2.8,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.6e-06,0.00035,1,1,0.75 -38690000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.069,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00039,0.00034,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.31,0.36,0.0056,2.6,3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.77 -38790000,-0.68,-0.013,-0.0034,0.74,1.8,1.9,0.075,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00033,0.0037,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.33,0.38,0.0056,2.8,3.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.8 -38890000,-0.68,-0.014,-0.0035,0.74,1.8,2,0.57,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00031,0.0038,0,0,-4.9e+02,4.8e-05,4.7e-05,0.00097,0.33,0.39,0.0056,3,3.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.7e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.83 +1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0,0,-1.2e+02,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0,0,-1.2e+02,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0,0,-1.2e+02,0.00022,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,5.9e-05,0.033,-0.0068,-0.26,0,0,-1.2e+02,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0,0,-1.2e+02,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0,0,-1.2e+02,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0,0,-1.2e+02,9e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.011,-0.013,5.9e-05,0.026,-0.009,-0.31,0,0,-1.2e+02,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0,0,-1.2e+02,-1.4e-05,-0.0029,-5.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.011,-0.013,4.9e-05,0.023,-0.0093,-0.34,0,0,-1.2e+02,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.011,-0.013,-1.1e-06,0.027,-0.011,-0.35,0,0,-1.2e+02,-0.00012,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0,0,-1.2e+02,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.011,-0.013,4.9e-05,0.025,-0.011,-0.38,0,0,-1.2e+02,-0.00023,-0.0036,-6.5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,-1.2e+02,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.011,-0.013,-8e-06,0.02,-0.0086,-0.39,0,0,-1.2e+02,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.011,-0.013,3.2e-05,0.023,-0.01,-0.4,0,0,-1.2e+02,-0.00034,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.011,-0.012,3.2e-06,0.018,-0.0091,-0.42,0,0,-1.2e+02,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.011,-0.013,-4.5e-06,0.022,-0.012,-0.43,0,0,-1.2e+02,-0.00044,-0.0041,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.011,-0.012,1.9e-05,0.017,-0.011,-0.44,0,0,-1.2e+02,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0,0,-1.2e+02,-0.00055,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,-1.2e+02,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0,0,-1.2e+02,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0,0,-1.2e+02,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0,0,-1.2e+02,-0.00067,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0,0,-1.2e+02,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0,0,-1.2e+02,-0.00079,-0.0047,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.01,-0.012,8.1e-05,0.017,-0.012,-0.54,0,0,-1.2e+02,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0,0,-1.2e+02,-0.00091,-0.0049,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-1.2e+02,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0,0,-1.2e+02,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0,0,-1.2e+02,-0.001,-0.005,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.01,-0.012,0.00019,0.014,-0.0096,-0.6,0,0,-1.2e+02,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.01,-0.012,0.00018,0.015,-0.011,-0.61,0,0,-1.2e+02,-0.0011,-0.0052,-7.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-1.2e+02,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0,0,-1.2e+02,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0,0,-1.2e+02,-0.0012,-0.0053,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0,0,-1.2e+02,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0,0,-1.2e+02,-0.0013,-0.0054,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0,0,-1.2e+02,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0,0,-1.2e+02,-0.0013,-0.0055,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-1.2e+02,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0,0,-1.2e+02,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0,0,-1.2e+02,-0.0014,-0.0055,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0096,-0.011,0.00033,0.0041,-0.0036,-0.74,0,0,-1.2e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0025,-0.75,0,0,-1.2e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-1.2e+02,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0094,-0.011,0.00031,0.0038,-0.0007,0.0028,0,0,-4.9e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00081,0.015,0,0,-4.9e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-4.9e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0094,-0.011,0.00032,0.0051,0.002,-0.011,0,0,-4.9e+02,-0.0014,-0.0056,-7.4e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-4.9e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0044,-0.005,0,0,-4.9e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0094,-0.011,0.00022,0.005,0.0045,-0.012,0,0,-4.9e+02,-0.0015,-0.0056,-7.5e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-4.9e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0093,-0.011,0.00023,0.0043,0.0055,-0.05,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-4.9e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0057,-0.052,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0093,-0.011,0.00016,0.0037,0.0057,-0.099,0,0,-4.9e+02,-0.0014,-0.0057,-7.6e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0093,-0.011,9.4e-05,0.0046,0.0053,-0.076,0,0,-4.9e+02,-0.0014,-0.0057,-7.6e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6790000,0.71,0.0012,-0.014,0.71,0.0049,0.0052,-0.11,0,0,-4.9e+02,-0.0014,-0.0057,-7.5e-05,0,0,-7e-05,0.21,8e-05,0.43,3.5e-05,0.00033,-0.0024,0,0,-4.9e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.11,0.11,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 +6890000,0.71,0.0013,-0.014,0.7,0.00052,0.0065,-0.12,0,0,-4.9e+02,-0.0015,-0.0057,-7.6e-05,0,0,-9.8e-05,0.21,1.3e-05,0.43,6.1e-07,0.00089,-0.00086,0,0,-4.9e+02,0.0013,0.0013,0.047,0.21,0.21,0.46,0.13,0.14,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 +6990000,0.71,0.0013,-0.014,0.71,-0.00025,0.0048,-0.12,0,0,-4.9e+02,-0.0014,-0.0057,-7.7e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.044,0.23,0.24,0.36,0.17,0.17,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7090000,0.71,0.0012,-0.014,0.71,-0.00081,0.0013,-0.13,0,0,-4.9e+02,-0.0014,-0.0057,-7.9e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00038,0.00025,-0.00041,0,0,-4.9e+02,0.0013,0.0013,0.043,0.27,0.27,0.29,0.2,0.21,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7190000,0.71,0.0013,-0.014,0.71,-0.0025,0.0021,-0.15,0,0,-4.9e+02,-0.0014,-0.0057,-7.8e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-4.9e+02,0.0013,0.0013,0.042,0.3,0.31,0.24,0.25,0.25,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 +7290000,0.71,0.0015,-0.014,0.71,-0.0044,0.01,-0.15,0,0,-4.9e+02,-0.0015,-0.0057,-7.5e-05,-0.00022,-0.00021,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00038,0,0,-4.9e+02,0.0013,0.0013,0.042,0.34,0.35,0.2,0.3,0.31,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7390000,0.71,0.0016,-0.014,0.71,-0.0037,0.015,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00029,-4.1e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00031,0,0,-4.9e+02,0.0013,0.0013,0.041,0.38,0.39,0.18,0.37,0.37,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7490000,0.71,0.0015,-0.014,0.71,-0.0038,0.012,-0.16,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00019,-7.7e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00079,-0.00042,0,0,-4.9e+02,0.0013,0.0013,0.041,0.43,0.43,0.15,0.44,0.45,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7590000,0.71,0.0017,-0.014,0.71,-0.0034,0.021,-0.17,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.0002,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-4.9e+02,0.0013,0.0013,0.04,0.48,0.48,0.14,0.53,0.53,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7690000,0.71,0.0017,-0.014,0.71,-0.0046,0.018,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.1e-05,-0.00025,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00033,0.00084,-0.00033,0,0,-4.9e+02,0.0014,0.0013,0.04,0.53,0.53,0.13,0.63,0.63,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 +7790000,0.71,0.0017,-0.014,0.71,-0.011,0.017,-0.16,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00037,5.8e-05,-0.0071,0.21,-1.7e-05,0.43,-0.00034,0.00079,-0.00038,0,0,-4.9e+02,0.0014,0.0013,0.04,0.58,0.58,0.12,0.74,0.74,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 +7890000,0.71,0.0017,-0.014,0.71,-0.011,0.022,-0.16,0,0,-4.9e+02,-0.0016,-0.0057,-7.2e-05,-0.00039,0.0002,-0.0096,0.21,-1.6e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-4.9e+02,0.0014,0.0014,0.04,0.64,0.63,0.11,0.87,0.86,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 +7990000,0.71,0.0017,-0.014,0.71,-0.0091,0.023,-0.16,0,0,-4.9e+02,-0.0016,-0.0056,-7.1e-05,-0.00038,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00086,-0.00038,0,0,-4.9e+02,0.0014,0.0014,0.04,0.7,0.68,0.1,1,0.99,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 +8090000,0.71,0.0017,-0.014,0.71,-0.0051,0.025,-0.17,0,0,-4.9e+02,-0.0016,-0.0056,-6.9e-05,-0.00031,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00034,0.0009,-0.00035,0,0,-4.9e+02,0.0014,0.0014,0.04,0.76,0.74,0.1,1.2,1.1,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8190000,0.71,0.0018,-0.014,0.71,-0.014,0.029,-0.18,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00045,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-4.9e+02,0.0014,0.0014,0.04,0.82,0.79,0.099,1.4,1.3,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8290000,0.71,0.0017,-0.014,0.71,-0.018,0.023,-0.17,0,0,-4.9e+02,-0.0015,-0.0057,-7.4e-05,-0.00057,0.00031,-0.017,0.21,-1e-05,0.43,-0.00032,0.00079,-0.00034,0,0,-4.9e+02,0.0014,0.0014,0.039,0.88,0.84,0.097,1.6,1.5,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8390000,0.71,0.0017,-0.014,0.71,-0.0012,0.00048,-0.17,0,0,-4.9e+02,-0.0015,-0.0056,-7.1e-05,-0.00052,0.00039,-0.021,0.21,-9.6e-06,0.43,-0.00031,0.00084,-0.00031,0,0,-4.9e+02,0.0014,0.0014,0.039,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,7e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8490000,0.71,0.0017,-0.014,0.71,-0.0029,0.0026,-0.17,0,0,-4.9e+02,-0.0015,-0.0056,-7.2e-05,-0.00052,0.00039,-0.025,0.21,-9.3e-06,0.43,-0.00032,0.0008,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.089,6.2e-05,6.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8590000,0.71,0.0022,-0.014,0.71,-0.00042,0.00097,-0.17,0,0,-4.9e+02,-0.0017,-0.0057,-7e-05,-0.00052,0.00039,-0.029,0.21,-1.2e-05,0.43,-0.00043,0.00076,-0.00028,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.088,6e-05,6.8e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8690000,0.71,0.0021,-0.014,0.71,-0.0034,0.003,-0.16,0,0,-4.9e+02,-0.0017,-0.0056,-6.7e-05,-0.00052,0.00039,-0.035,0.21,-1.1e-05,0.43,-0.00041,0.00085,-0.00029,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.088,5.8e-05,6.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8790000,0.71,0.002,-0.014,0.71,-0.0056,0.0053,-0.15,0,0,-4.9e+02,-0.0016,-0.0057,-7e-05,-0.00052,0.00043,-0.041,0.21,-9.5e-06,0.43,-0.00038,0.0008,-0.00029,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.087,5.6e-05,6.6e-05,2.4e-06,0.04,0.04,0.032,0.0013,6.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8890000,0.71,0.0019,-0.014,0.71,-0.0077,0.0061,-0.15,0,0,-4.9e+02,-0.0016,-0.0057,-7.3e-05,-0.00065,0.00043,-0.045,0.21,-8.2e-06,0.43,-0.00036,0.00078,-0.00033,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.086,5.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.03,0.0013,6.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +8990000,0.71,0.0019,-0.014,0.71,-0.01,0.0057,-0.14,0,0,-4.9e+02,-0.0015,-0.0058,-7.7e-05,-0.00088,0.00044,-0.051,0.21,-7e-06,0.43,-0.00032,0.00071,-0.00034,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.087,5.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.029,0.0013,6.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9090000,0.71,0.002,-0.014,0.71,-0.014,0.0071,-0.14,0,0,-4.9e+02,-0.0015,-0.0058,-7.7e-05,-0.001,0.00055,-0.053,0.21,-7.3e-06,0.43,-0.00034,0.00067,-0.00034,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.095,1.1e+02,1.1e+02,0.086,4.9e-05,6.2e-05,2.4e-06,0.04,0.04,0.028,0.0013,5.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9190000,0.71,0.0019,-0.014,0.71,-0.012,0.01,-0.14,0,0,-4.9e+02,-0.0015,-0.0056,-7.2e-05,-0.00088,0.0006,-0.057,0.21,-6.7e-06,0.43,-0.00033,0.00081,-0.00025,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.094,1.1e+02,1.1e+02,0.085,4.6e-05,6e-05,2.4e-06,0.04,0.04,0.027,0.0013,5.6e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9290000,0.71,0.0018,-0.014,0.71,-0.011,0.01,-0.14,0,0,-4.9e+02,-0.0014,-0.0056,-7.3e-05,-0.00098,0.0006,-0.061,0.21,-5.5e-06,0.43,-0.00028,0.00082,-0.00024,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.093,1.1e+02,1.1e+02,0.085,4.4e-05,5.8e-05,2.4e-06,0.04,0.04,0.025,0.0013,5.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9390000,0.71,0.0016,-0.014,0.71,-0.011,0.011,-0.14,0,0,-4.9e+02,-0.0014,-0.0056,-7.4e-05,-0.0011,0.0006,-0.065,0.21,-4.7e-06,0.43,-0.00024,0.00081,-0.00022,0,0,-4.9e+02,0.0013,0.0014,0.039,25,25,0.093,1.2e+02,1.2e+02,0.086,4.2e-05,5.7e-05,2.4e-06,0.04,0.04,0.024,0.0013,5.2e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9490000,0.71,0.0015,-0.014,0.71,-0.0079,0.013,-0.13,0,0,-4.9e+02,-0.0013,-0.0055,-7.1e-05,-0.001,0.00062,-0.068,0.21,-4.1e-06,0.43,-0.00021,0.00089,-0.00013,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.091,1.2e+02,1.2e+02,0.085,4e-05,5.5e-05,2.4e-06,0.04,0.04,0.023,0.0013,5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9590000,0.71,0.0017,-0.014,0.71,-0.01,0.019,-0.13,0,0,-4.9e+02,-0.0014,-0.0055,-6.8e-05,-0.0011,0.00082,-0.072,0.21,-4.9e-06,0.43,-0.00027,0.0009,-0.00013,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.09,1.3e+02,1.3e+02,0.085,3.8e-05,5.4e-05,2.4e-06,0.04,0.04,0.021,0.0013,4.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9690000,0.71,0.0019,-0.014,0.71,-0.018,0.019,-0.12,0,0,-4.9e+02,-0.0015,-0.0056,-7.2e-05,-0.0014,0.00095,-0.077,0.21,-5.2e-06,0.43,-0.00029,0.00079,-0.00017,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.089,1.3e+02,1.3e+02,0.086,3.6e-05,5.2e-05,2.4e-06,0.04,0.04,0.02,0.0013,4.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9790000,0.71,0.0018,-0.014,0.71,-0.013,0.023,-0.11,0,0,-4.9e+02,-0.0014,-0.0055,-7e-05,-0.0014,0.001,-0.082,0.21,-4.9e-06,0.43,-0.00027,0.00084,-0.0001,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.087,1.4e+02,1.4e+02,0.085,3.4e-05,5e-05,2.4e-06,0.04,0.04,0.019,0.0013,4.5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9890000,0.71,0.0019,-0.014,0.71,-0.017,0.026,-0.11,0,0,-4.9e+02,-0.0015,-0.0056,-7e-05,-0.0015,0.0011,-0.085,0.21,-5e-06,0.43,-0.00028,0.00081,-0.00011,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.084,1.4e+02,1.4e+02,0.085,3.2e-05,4.9e-05,2.4e-06,0.04,0.04,0.018,0.0013,4.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9990000,0.71,0.002,-0.014,0.71,-0.021,0.024,-0.1,0,0,-4.9e+02,-0.0015,-0.0056,-7.2e-05,-0.0017,0.0012,-0.089,0.21,-4.7e-06,0.43,-0.00028,0.00077,-0.00014,0,0,-4.9e+02,0.0013,0.0013,0.039,25,25,0.083,1.5e+02,1.5e+02,0.086,3.1e-05,4.7e-05,2.4e-06,0.04,0.04,0.017,0.0013,4.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +10090000,0.71,0.0021,-0.014,0.71,-0.023,0.029,-0.096,0,0,-4.9e+02,-0.0015,-0.0056,-7e-05,-0.0017,0.0013,-0.091,0.21,-5.1e-06,0.43,-0.00031,0.00077,-0.00013,0,0,-4.9e+02,0.0013,0.0012,0.039,25,25,0.08,1.6e+02,1.6e+02,0.085,2.9e-05,4.6e-05,2.4e-06,0.04,0.04,0.016,0.0013,4.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10190000,0.71,0.0022,-0.014,0.71,-0.034,0.026,-0.096,0,0,-4.9e+02,-0.0015,-0.0058,-7.6e-05,-0.0019,0.0013,-0.093,0.21,-4.9e-06,0.43,-0.0003,0.00064,-0.00016,0,0,-4.9e+02,0.0012,0.0012,0.039,25,25,0.078,1.7e+02,1.7e+02,0.084,2.7e-05,4.4e-05,2.4e-06,0.04,0.04,0.014,0.0013,4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10290000,0.71,0.0021,-0.013,0.71,-0.041,0.022,-0.084,0,0,-4.9e+02,-0.0015,-0.0059,-8e-05,-0.0021,0.0015,-0.098,0.21,-4.6e-06,0.43,-0.00029,0.00056,-0.00018,0,0,-4.9e+02,0.0012,0.0012,0.039,25,25,0.076,1.8e+02,1.8e+02,0.085,2.6e-05,4.2e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10390000,0.71,0.002,-0.013,0.71,0.009,-0.02,0.0093,0,0,-4.9e+02,-0.0015,-0.0059,-8.1e-05,-0.0021,0.0014,-0.098,0.21,-4.1e-06,0.43,-0.00026,0.00058,-0.00014,0,0,-4.9e+02,0.0012,0.0012,0.039,0.25,0.25,0.56,0.5,0.5,0.077,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10490000,0.71,0.0019,-0.013,0.71,0.007,-0.019,0.022,0,0,-4.9e+02,-0.0014,-0.0059,-8.5e-05,-0.0022,0.0014,-0.098,0.21,-3.7e-06,0.43,-0.00024,0.00052,-0.00017,0,0,-4.9e+02,0.0012,0.0012,0.039,0.26,0.26,0.55,0.51,0.51,0.079,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10590000,0.71,0.0023,-0.013,0.71,0.0059,-0.0077,0.024,0,0,-4.9e+02,-0.0015,-0.0059,-8.1e-05,-0.0024,0.0018,-0.098,0.21,-5e-06,0.43,-0.00032,0.00051,-0.00018,0,0,-4.9e+02,0.0012,0.0011,0.039,0.13,0.13,0.27,0.17,0.17,0.072,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10690000,0.71,0.0022,-0.013,0.71,0.0031,-0.0083,0.027,0,0,-4.9e+02,-0.0015,-0.0059,-8.3e-05,-0.0024,0.0018,-0.098,0.21,-4.6e-06,0.43,-0.0003,0.0005,-0.00018,0,0,-4.9e+02,0.0012,0.0011,0.039,0.14,0.14,0.26,0.18,0.18,0.077,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10790000,0.71,0.0021,-0.013,0.71,0.0032,-0.0057,0.021,0,0,-4.9e+02,-0.0015,-0.0059,-8.2e-05,-0.0025,0.0022,-0.098,0.21,-4.5e-06,0.43,-0.00029,0.00054,-0.00017,0,0,-4.9e+02,0.0012,0.0011,0.038,0.093,0.094,0.17,0.11,0.11,0.071,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10890000,0.71,0.002,-0.013,0.71,0.0018,-0.0056,0.016,0,0,-4.9e+02,-0.0014,-0.0059,-8.3e-05,-0.0025,0.0021,-0.098,0.21,-4.2e-06,0.43,-0.00027,0.00055,-0.00016,0,0,-4.9e+02,0.0011,0.0011,0.038,0.1,0.1,0.16,0.11,0.11,0.074,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +10990000,0.71,0.0018,-0.014,0.71,0.0065,-0.00059,0.011,0,0,-4.9e+02,-0.0013,-0.0057,-8.1e-05,-0.0025,0.0031,-0.098,0.21,-3.7e-06,0.43,-0.00025,0.00069,-0.00012,0,0,-4.9e+02,0.0011,0.001,0.038,0.079,0.08,0.12,0.079,0.079,0.071,1.7e-05,3.1e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11090000,0.71,0.0019,-0.014,0.71,0.0064,0.003,0.014,0,0,-4.9e+02,-0.0014,-0.0056,-7.7e-05,-0.0023,0.0029,-0.098,0.21,-3.8e-06,0.43,-0.00026,0.00076,-7.8e-05,0,0,-4.9e+02,0.0011,0.00099,0.038,0.09,0.091,0.12,0.085,0.085,0.073,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11190000,0.71,0.0018,-0.014,0.71,0.0098,0.0044,0.0027,0,0,-4.9e+02,-0.0013,-0.0057,-8e-05,-0.0021,0.004,-0.098,0.21,-3.9e-06,0.43,-0.00027,0.00077,-9.5e-05,0,0,-4.9e+02,0.00098,0.00092,0.038,0.074,0.075,0.091,0.066,0.066,0.068,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11290000,0.71,0.0017,-0.014,0.71,0.0089,0.003,0.0014,0,0,-4.9e+02,-0.0013,-0.0057,-8.5e-05,-0.0025,0.0043,-0.098,0.21,-3.5e-06,0.43,-0.00024,0.00071,-0.00012,0,0,-4.9e+02,0.00098,0.00091,0.038,0.086,0.087,0.087,0.072,0.072,0.071,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11390000,0.71,0.0017,-0.013,0.71,0.0044,0.002,-0.0044,0,0,-4.9e+02,-0.0013,-0.0058,-8.7e-05,-0.003,0.004,-0.098,0.21,-3.4e-06,0.43,-0.00024,0.00064,-0.00017,0,0,-4.9e+02,0.00087,0.00082,0.038,0.072,0.073,0.072,0.058,0.058,0.067,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11490000,0.71,0.0015,-0.013,0.71,0.00059,-0.00071,-0.0044,0,0,-4.9e+02,-0.0012,-0.006,-9.4e-05,-0.0036,0.0048,-0.098,0.21,-3.2e-06,0.43,-0.00021,0.00054,-0.00023,0,0,-4.9e+02,0.00086,0.00081,0.038,0.083,0.086,0.069,0.064,0.064,0.068,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11590000,0.71,0.0014,-0.013,0.71,-0.0025,-0.00042,-0.01,0,0,-4.9e+02,-0.0012,-0.006,-9.6e-05,-0.0041,0.0049,-0.098,0.21,-2.9e-06,0.43,-0.00018,0.00052,-0.00024,0,0,-4.9e+02,0.00075,0.00072,0.038,0.07,0.072,0.059,0.054,0.054,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11690000,0.71,0.0012,-0.013,0.71,-0.0041,-0.0014,-0.016,0,0,-4.9e+02,-0.0011,-0.006,-9.9e-05,-0.0049,0.005,-0.098,0.21,-2.5e-06,0.43,-0.00013,0.00051,-0.00027,0,0,-4.9e+02,0.00075,0.00071,0.038,0.082,0.084,0.057,0.06,0.06,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11790000,0.71,0.0011,-0.013,0.71,-0.008,0.00022,-0.018,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0066,0.0052,-0.098,0.21,-2.4e-06,0.43,-0.00011,0.00049,-0.00028,0,0,-4.9e+02,0.00065,0.00063,0.038,0.068,0.07,0.051,0.051,0.051,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11890000,0.71,0.001,-0.013,0.71,-0.009,-0.0025,-0.02,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0072,0.0057,-0.098,0.21,-2.4e-06,0.43,-7.7e-05,0.00045,-0.00033,0,0,-4.9e+02,0.00065,0.00062,0.038,0.08,0.082,0.049,0.058,0.058,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11990000,0.71,0.0014,-0.013,0.71,-0.012,0.0022,-0.026,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0067,0.0062,-0.097,0.21,-3.3e-06,0.43,-0.00015,0.00047,-0.00032,0,0,-4.9e+02,0.00056,0.00055,0.037,0.066,0.068,0.045,0.049,0.049,0.062,9.2e-06,1.6e-05,2.3e-06,0.026,0.028,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +12090000,0.71,0.0015,-0.013,0.71,-0.014,0.0055,-0.032,0,0,-4.9e+02,-0.0012,-0.006,-9.6e-05,-0.0056,0.0054,-0.097,0.21,-3.4e-06,0.43,-0.00018,0.00052,-0.00028,0,0,-4.9e+02,0.00056,0.00055,0.037,0.077,0.079,0.045,0.056,0.057,0.062,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12190000,0.71,0.0012,-0.013,0.71,-0.0072,0.0049,-0.026,0,0,-4.9e+02,-0.0011,-0.0059,-9.8e-05,-0.0054,0.0057,-0.099,0.21,-2.7e-06,0.43,-0.00013,0.00059,-0.00027,0,0,-4.9e+02,0.00048,0.00048,0.037,0.064,0.066,0.041,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12290000,0.71,0.0011,-0.013,0.71,-0.0085,0.0054,-0.026,0,0,-4.9e+02,-0.001,-0.0059,-9.8e-05,-0.0059,0.0053,-0.099,0.21,-2.4e-06,0.43,-0.0001,0.0006,-0.00026,0,0,-4.9e+02,0.00048,0.00048,0.037,0.073,0.076,0.042,0.056,0.056,0.06,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12390000,0.71,0.001,-0.013,0.71,-0.0057,0.004,-0.023,0,0,-4.9e+02,-0.0011,-0.0059,-0.0001,-0.0045,0.007,-0.1,0.21,-2.8e-06,0.43,-0.00014,0.0006,-0.00025,0,0,-4.9e+02,0.00042,0.00043,0.037,0.061,0.063,0.039,0.048,0.048,0.058,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12490000,0.71,0.00098,-0.013,0.71,-0.0074,0.0036,-0.027,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0049,0.0082,-0.1,0.21,-3.1e-06,0.43,-0.00017,0.00054,-0.00025,0,0,-4.9e+02,0.00042,0.00042,0.037,0.069,0.072,0.04,0.055,0.055,0.058,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12590000,0.71,0.0012,-0.013,0.71,-0.015,0.0044,-0.033,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0042,0.0074,-0.1,0.21,-3.3e-06,0.43,-0.00021,0.00051,-0.00024,0,0,-4.9e+02,0.00037,0.00038,0.037,0.058,0.059,0.038,0.047,0.048,0.057,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12690000,0.71,0.0014,-0.013,0.71,-0.018,0.0053,-0.037,0,0,-4.9e+02,-0.0012,-0.006,-0.0001,-0.0024,0.0088,-0.1,0.21,-4.3e-06,0.43,-0.00028,0.00049,-0.00025,0,0,-4.9e+02,0.00037,0.00038,0.037,0.065,0.067,0.039,0.055,0.055,0.057,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12790000,0.71,0.0013,-0.013,0.71,-0.02,0.0033,-0.041,0,0,-4.9e+02,-0.0012,-0.006,-0.0001,-0.0039,0.0076,-0.1,0.21,-3.6e-06,0.43,-0.00023,0.00048,-0.00027,0,0,-4.9e+02,0.00033,0.00034,0.037,0.054,0.056,0.037,0.047,0.047,0.056,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12890000,0.71,0.0011,-0.013,0.71,-0.02,0.002,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0052,0.0072,-0.1,0.21,-3.2e-06,0.43,-0.00019,0.00047,-0.00026,0,0,-4.9e+02,0.00033,0.00034,0.037,0.061,0.063,0.038,0.054,0.055,0.057,6e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +12990000,0.71,0.001,-0.013,0.71,-0.0092,0.0023,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.0001,-0.0027,0.0076,-0.1,0.21,-3e-06,0.43,-0.0002,0.00058,-0.0002,0,0,-4.9e+02,0.0003,0.00031,0.037,0.051,0.053,0.037,0.047,0.047,0.055,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13090000,0.71,0.00097,-0.013,0.71,-0.0099,0.00034,-0.039,0,0,-4.9e+02,-0.0011,-0.006,-0.00011,-0.0038,0.0092,-0.1,0.21,-3.4e-06,0.43,-0.00022,0.00052,-0.00023,0,0,-4.9e+02,0.0003,0.00031,0.037,0.057,0.059,0.038,0.054,0.054,0.056,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13190000,0.71,0.00097,-0.013,0.71,-0.0025,0.0012,-0.034,0,0,-4.9e+02,-0.0011,-0.006,-0.00011,-0.002,0.011,-0.11,0.21,-3.8e-06,0.43,-0.00025,0.00057,-0.00021,0,0,-4.9e+02,0.00027,0.00029,0.037,0.048,0.05,0.037,0.047,0.047,0.054,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13290000,0.71,0.00081,-0.013,0.71,-0.00098,0.0019,-0.029,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0035,0.009,-0.11,0.21,-2.8e-06,0.43,-0.00019,0.00058,-0.00019,0,0,-4.9e+02,0.00027,0.00028,0.037,0.054,0.055,0.038,0.054,0.054,0.055,5.1e-06,8.9e-06,2.3e-06,0.015,0.019,0.0097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13390000,0.71,0.00072,-0.013,0.71,8e-05,0.0026,-0.024,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0029,0.0083,-0.11,0.21,-2.6e-06,0.43,-0.00017,0.00063,-0.00019,0,0,-4.9e+02,0.00025,0.00026,0.037,0.045,0.047,0.037,0.047,0.047,0.054,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13490000,0.71,0.00072,-0.013,0.71,5e-05,0.0027,-0.022,0,0,-4.9e+02,-0.001,-0.0059,-0.0001,-0.0029,0.0075,-0.11,0.21,-2.2e-06,0.43,-0.00016,0.00064,-0.00017,0,0,-4.9e+02,0.00025,0.00026,0.037,0.05,0.052,0.038,0.054,0.054,0.055,4.7e-06,8.2e-06,2.3e-06,0.014,0.018,0.009,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13590000,0.71,0.00074,-0.013,0.71,-0.00015,0.003,-0.024,0,0,-4.9e+02,-0.001,-0.006,-0.0001,-0.0027,0.0087,-0.11,0.21,-2.7e-06,0.43,-0.00019,0.00063,-0.00019,0,0,-4.9e+02,0.00023,0.00025,0.037,0.042,0.044,0.037,0.046,0.047,0.054,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13690000,0.71,0.00072,-0.013,0.71,0.00078,0.0055,-0.029,0,0,-4.9e+02,-0.001,-0.0059,-9.9e-05,-0.0021,0.0075,-0.11,0.21,-2.3e-06,0.43,-0.00017,0.00065,-0.00016,0,0,-4.9e+02,0.00023,0.00024,0.037,0.047,0.049,0.038,0.053,0.054,0.055,4.3e-06,7.7e-06,2.3e-06,0.013,0.017,0.0083,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13790000,0.71,0.00076,-0.013,0.71,0.0005,0.0022,-0.03,0,0,-4.9e+02,-0.0011,-0.006,-9.9e-05,-0.00065,0.0082,-0.11,0.21,-2.7e-06,0.43,-0.00021,0.00066,-0.00014,0,0,-4.9e+02,0.00022,0.00023,0.037,0.04,0.041,0.036,0.046,0.046,0.053,4.2e-06,7.3e-06,2.3e-06,0.013,0.016,0.0078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13890000,0.71,0.0006,-0.013,0.71,0.0023,0.0023,-0.035,0,0,-4.9e+02,-0.001,-0.0059,-9.9e-05,-0.002,0.0071,-0.11,0.21,-2e-06,0.43,-0.00016,0.00066,-0.00015,0,0,-4.9e+02,0.00022,0.00023,0.037,0.044,0.046,0.037,0.053,0.053,0.055,4e-06,7.1e-06,2.3e-06,0.012,0.016,0.0076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13990000,0.71,0.00067,-0.013,0.71,0.0018,0.00057,-0.034,0,0,-4.9e+02,-0.001,-0.0059,-9.8e-05,-0.00073,0.0076,-0.11,0.21,-2.3e-06,0.43,-0.0002,0.00066,-0.00013,0,0,-4.9e+02,0.00021,0.00022,0.037,0.037,0.039,0.036,0.046,0.046,0.054,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0071,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +14090000,0.71,0.00073,-0.013,0.71,0.0013,0.0019,-0.035,0,0,-4.9e+02,-0.0011,-0.0059,-9.4e-05,0.00078,0.0065,-0.11,0.21,-2e-06,0.43,-0.0002,0.0007,-8.9e-05,0,0,-4.9e+02,0.00021,0.00022,0.037,0.041,0.043,0.036,0.053,0.053,0.054,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14190000,0.71,0.00069,-0.014,0.71,0.0044,0.0018,-0.037,0,0,-4.9e+02,-0.0011,-0.0059,-9.3e-05,0.0013,0.0062,-0.11,0.21,-1.8e-06,0.43,-0.00019,0.00072,-7.1e-05,0,0,-4.9e+02,0.0002,0.00021,0.037,0.035,0.037,0.035,0.046,0.046,0.054,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14290000,0.71,0.00076,-0.014,0.71,0.0046,0.0031,-0.035,0,0,-4.9e+02,-0.0011,-0.0059,-9.2e-05,0.0021,0.0062,-0.11,0.21,-1.9e-06,0.43,-0.0002,0.00072,-5.3e-05,0,0,-4.9e+02,0.0002,0.00021,0.037,0.039,0.04,0.036,0.052,0.052,0.055,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14390000,0.71,0.00064,-0.014,0.71,0.007,0.0049,-0.037,0,0,-4.9e+02,-0.0011,-0.0058,-8.9e-05,0.0018,0.0047,-0.11,0.21,-1.1e-06,0.43,-0.00016,0.00075,-3.7e-05,0,0,-4.9e+02,0.00019,0.0002,0.037,0.033,0.035,0.034,0.046,0.046,0.053,3.4e-06,6e-06,2.3e-06,0.011,0.014,0.0059,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14490000,0.71,0.00053,-0.014,0.71,0.008,0.0064,-0.041,0,0,-4.9e+02,-0.001,-0.0058,-8.9e-05,0.00054,0.0041,-0.11,0.21,-5.6e-07,0.43,-0.00014,0.00072,-3.7e-05,0,0,-4.9e+02,0.00019,0.0002,0.037,0.036,0.038,0.035,0.052,0.052,0.054,3.3e-06,5.8e-06,2.3e-06,0.011,0.014,0.0057,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14590000,0.71,0.00043,-0.013,0.71,0.0061,0.0048,-0.041,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.00033,0.0039,-0.11,0.21,-4.7e-07,0.43,-0.00013,0.00069,-5.1e-05,0,0,-4.9e+02,0.00018,0.00019,0.037,0.031,0.033,0.033,0.045,0.045,0.054,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0053,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14690000,0.71,0.00038,-0.013,0.71,0.0078,0.0029,-0.038,0,0,-4.9e+02,-0.001,-0.0058,-8.7e-05,-0.00028,0.003,-0.11,0.21,-7.5e-08,0.43,-0.00012,0.0007,-3.6e-05,0,0,-4.9e+02,0.00018,0.00019,0.037,0.034,0.036,0.034,0.051,0.052,0.054,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14790000,0.71,0.00036,-0.013,0.71,0.0055,0.0014,-0.033,0,0,-4.9e+02,-0.001,-0.0058,-8.6e-05,-0.00044,0.0028,-0.12,0.21,-1.3e-07,0.43,-0.00012,0.00068,-3.7e-05,0,0,-4.9e+02,0.00017,0.00018,0.037,0.03,0.031,0.032,0.045,0.045,0.053,3e-06,5.2e-06,2.3e-06,0.0098,0.013,0.0048,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14890000,0.71,0.00032,-0.013,0.71,0.0077,0.0031,-0.037,0,0,-4.9e+02,-0.001,-0.0058,-8.5e-05,-0.00068,0.0022,-0.12,0.21,1.4e-07,0.43,-0.00011,0.00068,-3.4e-05,0,0,-4.9e+02,0.00017,0.00018,0.037,0.032,0.034,0.032,0.051,0.051,0.055,2.9e-06,5.1e-06,2.3e-06,0.0097,0.013,0.0046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +14990000,0.71,0.00028,-0.013,0.71,0.0068,0.0021,-0.032,0,0,-4.9e+02,-0.001,-0.0059,-8.7e-05,-0.0012,0.0027,-0.12,0.21,-6.2e-08,0.43,-0.00012,0.00066,-4.6e-05,0,0,-4.9e+02,0.00017,0.00017,0.037,0.028,0.03,0.031,0.045,0.045,0.053,2.8e-06,4.9e-06,2.3e-06,0.0094,0.013,0.0043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15090000,0.71,0.00021,-0.013,0.71,0.0075,0.0021,-0.035,0,0,-4.9e+02,-0.001,-0.0059,-8.8e-05,-0.0013,0.0031,-0.12,0.21,-1.6e-07,0.43,-0.00013,0.00064,-4.7e-05,0,0,-4.9e+02,0.00017,0.00017,0.037,0.031,0.032,0.031,0.05,0.051,0.054,2.7e-06,4.8e-06,2.3e-06,0.0093,0.012,0.0041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15190000,0.71,0.00017,-0.013,0.71,0.0073,0.0027,-0.033,0,0,-4.9e+02,-0.00099,-0.0059,-8.9e-05,-0.0019,0.0034,-0.12,0.21,-1.5e-07,0.43,-0.00014,0.00061,-5.4e-05,0,0,-4.9e+02,0.00016,0.00017,0.037,0.027,0.028,0.03,0.044,0.045,0.053,2.6e-06,4.6e-06,2.3e-06,0.0091,0.012,0.0038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15290000,0.71,0.00019,-0.013,0.71,0.0077,0.0037,-0.03,0,0,-4.9e+02,-0.001,-0.0059,-8.7e-05,-0.00097,0.0032,-0.12,0.21,-9e-08,0.43,-0.00015,0.00061,-2.9e-05,0,0,-4.9e+02,0.00016,0.00017,0.037,0.029,0.031,0.03,0.05,0.05,0.054,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15390000,0.71,0.0002,-0.013,0.71,0.007,0.005,-0.028,0,0,-4.9e+02,-0.001,-0.0058,-8.3e-05,-0.00013,0.0017,-0.12,0.21,2.8e-07,0.43,-0.00014,0.00064,-5.8e-06,0,0,-4.9e+02,0.00016,0.00016,0.037,0.025,0.027,0.028,0.044,0.044,0.053,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15490000,0.71,0.00022,-0.013,0.71,0.0086,0.0041,-0.028,0,0,-4.9e+02,-0.001,-0.0059,-8.6e-05,-0.00053,0.003,-0.12,0.21,-1.8e-07,0.43,-0.00016,0.00061,-2.4e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.027,0.029,0.029,0.049,0.05,0.054,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15590000,0.71,0.00018,-0.013,0.71,0.0072,0.0031,-0.027,0,0,-4.9e+02,-0.001,-0.0059,-8.8e-05,-0.0012,0.0037,-0.12,0.21,-5.4e-07,0.43,-0.00016,0.0006,-4.9e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.024,0.026,0.027,0.044,0.044,0.053,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15690000,0.71,0.00022,-0.013,0.71,0.0074,0.0032,-0.028,0,0,-4.9e+02,-0.001,-0.0059,-8.9e-05,-0.00068,0.0041,-0.12,0.21,-8.5e-07,0.43,-0.00017,0.0006,-5.2e-05,0,0,-4.9e+02,0.00016,0.00016,0.037,0.026,0.028,0.027,0.049,0.049,0.053,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15790000,0.71,0.00019,-0.013,0.71,0.0081,0.0017,-0.03,0,0,-4.9e+02,-0.001,-0.0059,-8.8e-05,-0.00088,0.0043,-0.12,0.21,-9.6e-07,0.43,-0.00018,0.00059,-5.6e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.023,0.025,0.026,0.043,0.044,0.052,2.2e-06,3.9e-06,2.3e-06,0.0082,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15890000,0.71,0.0002,-0.013,0.71,0.0088,0.0016,-0.028,0,0,-4.9e+02,-0.0011,-0.0059,-8.8e-05,-0.00015,0.0046,-0.12,0.21,-1.2e-06,0.43,-0.00019,0.00059,-4.7e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.025,0.027,0.026,0.048,0.049,0.053,2.2e-06,3.8e-06,2.3e-06,0.0081,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15990000,0.71,0.00018,-0.013,0.71,0.0085,0.0017,-0.024,0,0,-4.9e+02,-0.0011,-0.0059,-8.3e-05,0.00049,0.0038,-0.12,0.21,-1e-06,0.43,-0.0002,0.0006,-2.9e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.022,0.024,0.025,0.043,0.043,0.052,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +16090000,0.71,0.00021,-0.013,0.71,0.011,0.0034,-0.02,0,0,-4.9e+02,-0.0011,-0.0059,-7.9e-05,0.0013,0.0025,-0.12,0.21,-7.5e-07,0.43,-0.00017,0.00065,-1.3e-05,0,0,-4.9e+02,0.00015,0.00015,0.037,0.024,0.026,0.024,0.048,0.049,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16190000,0.71,0.00026,-0.013,0.71,0.01,0.0036,-0.019,0,0,-4.9e+02,-0.0011,-0.0059,-7.8e-05,0.002,0.0027,-0.12,0.21,-1.1e-06,0.43,-0.00018,0.00065,-6.5e-06,0,0,-4.9e+02,0.00015,0.00014,0.037,0.021,0.023,0.023,0.043,0.043,0.052,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16290000,0.71,0.00028,-0.014,0.71,0.012,0.0046,-0.02,0,0,-4.9e+02,-0.0011,-0.0058,-7.4e-05,0.0024,0.0014,-0.12,0.21,-5.8e-07,0.43,-0.00017,0.00067,8.3e-06,0,0,-4.9e+02,0.00015,0.00014,0.037,0.023,0.025,0.023,0.048,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16390000,0.71,0.00033,-0.014,0.71,0.01,0.0031,-0.019,0,0,-4.9e+02,-0.0011,-0.0058,-7.5e-05,0.0035,0.0025,-0.12,0.21,-1.4e-06,0.43,-0.00019,0.00066,1.3e-05,0,0,-4.9e+02,0.00014,0.00014,0.037,0.02,0.023,0.022,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0075,0.0098,0.002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16490000,0.71,0.00042,-0.014,0.71,0.0088,0.0044,-0.022,0,0,-4.9e+02,-0.0011,-0.0058,-7.4e-05,0.0044,0.0027,-0.12,0.21,-1.6e-06,0.43,-0.0002,0.00066,2.7e-05,0,0,-4.9e+02,0.00014,0.00014,0.037,0.022,0.024,0.022,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0019,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16590000,0.71,0.00052,-0.013,0.71,0.0067,0.0053,-0.023,0,0,-4.9e+02,-0.0012,-0.0058,-7.5e-05,0.0045,0.0024,-0.12,0.21,-1.6e-06,0.43,-0.00019,0.00065,2.3e-05,0,0,-4.9e+02,0.00014,0.00014,0.037,0.02,0.022,0.021,0.042,0.042,0.05,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0095,0.0018,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16690000,0.71,0.00049,-0.013,0.71,0.0076,0.0056,-0.019,0,0,-4.9e+02,-0.0011,-0.0059,-7.8e-05,0.0039,0.0031,-0.12,0.21,-1.8e-06,0.43,-0.00019,0.00065,1.2e-05,0,0,-4.9e+02,0.00014,0.00014,0.037,0.021,0.024,0.021,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0017,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16790000,0.71,0.00048,-0.013,0.71,0.0057,0.0063,-0.018,0,0,-4.9e+02,-0.0011,-0.0058,-7.9e-05,0.0037,0.0027,-0.12,0.21,-1.7e-06,0.43,-0.00017,0.00065,-6e-07,0,0,-4.9e+02,0.00014,0.00013,0.037,0.019,0.021,0.02,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0093,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16890000,0.71,0.00054,-0.013,0.71,0.0055,0.0072,-0.016,0,0,-4.9e+02,-0.0012,-0.0059,-8.1e-05,0.0041,0.0033,-0.13,0.21,-2e-06,0.43,-0.00018,0.00064,4e-06,0,0,-4.9e+02,0.00014,0.00013,0.037,0.02,0.023,0.02,0.046,0.047,0.05,1.6e-06,2.8e-06,2.3e-06,0.007,0.0092,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +16990000,0.71,0.00051,-0.013,0.71,0.0055,0.0049,-0.015,0,0,-4.9e+02,-0.0012,-0.0059,-8.1e-05,0.004,0.0043,-0.13,0.21,-2.5e-06,0.43,-0.0002,0.00063,-6.1e-06,0,0,-4.9e+02,0.00013,0.00013,0.037,0.018,0.021,0.019,0.041,0.042,0.049,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17090000,0.71,0.00055,-0.013,0.71,0.0058,0.0064,-0.015,0,0,-4.9e+02,-0.0012,-0.0059,-8e-05,0.005,0.0046,-0.13,0.21,-2.8e-06,0.43,-0.00022,0.00063,6.2e-06,0,0,-4.9e+02,0.00014,0.00013,0.037,0.02,0.022,0.019,0.046,0.047,0.049,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17190000,0.71,0.0006,-0.013,0.71,0.0059,0.0074,-0.016,0,0,-4.9e+02,-0.0012,-0.0059,-7.6e-05,0.0057,0.0045,-0.13,0.21,-3.1e-06,0.43,-0.00022,0.00064,8.8e-06,0,0,-4.9e+02,0.00013,0.00013,0.037,0.018,0.02,0.018,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0068,0.0087,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17290000,0.71,0.00063,-0.013,0.71,0.0077,0.0081,-0.011,0,0,-4.9e+02,-0.0012,-0.0059,-7.8e-05,0.0061,0.0055,-0.13,0.21,-3.4e-06,0.43,-0.00023,0.00063,1.1e-05,0,0,-4.9e+02,0.00013,0.00013,0.037,0.019,0.022,0.018,0.045,0.046,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0086,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17390000,0.71,0.00068,-0.013,0.71,0.0075,0.0085,-0.0095,0,0,-4.9e+02,-0.0012,-0.0059,-7.2e-05,0.0069,0.0052,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00063,2.9e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.017,0.02,0.017,0.041,0.041,0.048,1.4e-06,2.5e-06,2.2e-06,0.0066,0.0085,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17490000,0.71,0.00063,-0.013,0.71,0.0091,0.0086,-0.0078,0,0,-4.9e+02,-0.0012,-0.0059,-7.2e-05,0.0063,0.005,-0.13,0.21,-3.4e-06,0.43,-0.00025,0.00063,2.4e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.019,0.021,0.017,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17590000,0.71,0.0006,-0.013,0.71,0.0099,0.0079,-0.0024,0,0,-4.9e+02,-0.0012,-0.0059,-6.9e-05,0.0067,0.0052,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00064,2.2e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.017,0.019,0.017,0.04,0.041,0.048,1.4e-06,2.3e-06,2.2e-06,0.0065,0.0083,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17690000,0.71,0.00057,-0.013,0.71,0.011,0.0094,-0.003,0,0,-4.9e+02,-0.0012,-0.0059,-6.8e-05,0.0068,0.005,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00064,3e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.045,0.046,0.048,1.3e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17790000,0.71,0.00056,-0.013,0.71,0.012,0.01,-0.0042,0,0,-4.9e+02,-0.0012,-0.0059,-5.9e-05,0.0077,0.0039,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00066,4e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.0081,0.001,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17890000,0.71,0.00055,-0.013,0.71,0.015,0.011,-0.004,0,0,-4.9e+02,-0.0012,-0.0059,-5.7e-05,0.0076,0.0032,-0.13,0.21,-3.2e-06,0.43,-0.00025,0.00067,4.4e-05,0,0,-4.9e+02,0.00013,0.00012,0.037,0.018,0.02,0.016,0.044,0.045,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.00097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17990000,0.71,0.00048,-0.013,0.71,0.016,0.0084,-0.0027,0,0,-4.9e+02,-0.0012,-0.0059,-5.6e-05,0.0073,0.0035,-0.13,0.21,-3.3e-06,0.43,-0.00026,0.00066,4.1e-05,0,0,-4.9e+02,0.00012,0.00012,0.037,0.016,0.019,0.015,0.04,0.041,0.046,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0078,0.00092,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +18090000,0.71,0.00047,-0.013,0.71,0.017,0.0076,-0.00044,0,0,-4.9e+02,-0.0012,-0.0059,-6.1e-05,0.0068,0.0045,-0.13,0.21,-3.5e-06,0.43,-0.00027,0.00064,3.6e-05,0,0,-4.9e+02,0.00012,0.00012,0.037,0.017,0.02,0.015,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00089,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18190000,0.71,0.00043,-0.013,0.71,0.018,0.0086,0.001,0,0,-4.9e+02,-0.0012,-0.0059,-5.7e-05,0.007,0.0041,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00065,3.7e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.018,0.014,0.04,0.041,0.046,1.2e-06,2e-06,2.2e-06,0.0061,0.0077,0.00085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18290000,0.71,0.00035,-0.013,0.71,0.018,0.0081,0.0022,0,0,-4.9e+02,-0.0012,-0.0059,-5.9e-05,0.0066,0.0044,-0.13,0.21,-3.5e-06,0.43,-0.00027,0.00064,3.2e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.017,0.02,0.014,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00082,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18390000,0.71,0.00031,-0.013,0.71,0.02,0.01,0.0035,0,0,-4.9e+02,-0.0012,-0.0059,-5.3e-05,0.0063,0.0036,-0.13,0.21,-3.3e-06,0.43,-0.00026,0.00065,3.3e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.045,1.1e-06,1.9e-06,2.2e-06,0.006,0.0075,0.00078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18490000,0.71,0.00037,-0.013,0.71,0.021,0.011,0.0031,0,0,-4.9e+02,-0.0012,-0.0059,-5.2e-05,0.0069,0.0037,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00066,3.7e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.02,0.014,0.043,0.045,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18590000,0.71,0.00039,-0.013,0.71,0.02,0.012,0.0014,0,0,-4.9e+02,-0.0012,-0.0059,-4.4e-05,0.0077,0.0031,-0.13,0.21,-3.6e-06,0.43,-0.00026,0.00067,4.2e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0073,0.00072,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18690000,0.71,0.0003,-0.013,0.71,0.022,0.012,-0.00039,0,0,-4.9e+02,-0.0012,-0.0059,-4.6e-05,0.007,0.0031,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00066,3.6e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0072,0.0007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18790000,0.71,0.00032,-0.013,0.71,0.021,0.011,-0.00061,0,0,-4.9e+02,-0.0012,-0.0059,-4.5e-05,0.0072,0.0037,-0.13,0.21,-3.7e-06,0.43,-0.00026,0.00065,3.3e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00067,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18890000,0.71,0.00041,-0.013,0.71,0.021,0.013,1.6e-05,0,0,-4.9e+02,-0.0012,-0.0059,-3.9e-05,0.0082,0.0032,-0.13,0.21,-3.8e-06,0.43,-0.00027,0.00067,4.7e-05,0,0,-4.9e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +18990000,0.71,0.00046,-0.013,0.71,0.021,0.014,-0.0012,0,0,-4.9e+02,-0.0013,-0.0059,-3.3e-05,0.0088,0.0033,-0.13,0.21,-4.1e-06,0.43,-0.00028,0.00068,4.8e-05,0,0,-4.9e+02,0.00011,0.0001,0.037,0.015,0.017,0.012,0.039,0.04,0.044,9.7e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00062,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19090000,0.71,0.0005,-0.013,0.71,0.021,0.015,0.0018,0,0,-4.9e+02,-0.0013,-0.0059,-3.3e-05,0.0094,0.0036,-0.13,0.21,-4.3e-06,0.43,-0.00029,0.00069,5.2e-05,0,0,-4.9e+02,0.00011,0.0001,0.037,0.016,0.019,0.012,0.042,0.044,0.044,9.6e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.0006,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19190000,0.71,0.00055,-0.013,0.71,0.02,0.015,0.0019,0,0,-4.9e+02,-0.0013,-0.0059,-2.7e-05,0.0099,0.0037,-0.13,0.21,-4.5e-06,0.43,-0.00031,0.00069,5.6e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.043,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.00058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19290000,0.71,0.00058,-0.013,0.71,0.02,0.015,0.0046,0,0,-4.9e+02,-0.0013,-0.0059,-3e-05,0.0098,0.0041,-0.13,0.21,-4.6e-06,0.43,-0.00031,0.00068,5.8e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.015,0.019,0.012,0.042,0.044,0.043,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19390000,0.71,0.00054,-0.013,0.71,0.019,0.014,0.0084,0,0,-4.9e+02,-0.0013,-0.0059,-2.3e-05,0.0097,0.004,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00068,5.3e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.014,0.017,0.011,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0055,0.0066,0.00054,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19490000,0.71,0.00055,-0.013,0.71,0.019,0.015,0.0049,0,0,-4.9e+02,-0.0013,-0.0059,-1.8e-05,0.0098,0.0033,-0.13,0.21,-4.4e-06,0.43,-0.0003,0.00069,5.6e-05,0,0,-4.9e+02,0.00011,0.0001,0.036,0.015,0.018,0.011,0.042,0.044,0.043,8.8e-07,1.4e-06,2.1e-06,0.0054,0.0066,0.00052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19590000,0.71,0.00063,-0.013,0.71,0.017,0.014,0.0043,0,0,-4.9e+02,-0.0013,-0.0059,-6.7e-06,0.011,0.003,-0.13,0.21,-4.6e-06,0.43,-0.00031,0.0007,6.4e-05,0,0,-4.9e+02,0.00011,9.8e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.6e-07,1.4e-06,2.1e-06,0.0054,0.0065,0.0005,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19690000,0.71,0.00067,-0.013,0.71,0.017,0.012,0.0058,0,0,-4.9e+02,-0.0013,-0.0059,-1e-05,0.011,0.0036,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.0007,5.7e-05,0,0,-4.9e+02,0.00011,9.8e-05,0.036,0.015,0.018,0.011,0.042,0.043,0.042,8.4e-07,1.4e-06,2.1e-06,0.0053,0.0065,0.00049,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19790000,0.71,0.00074,-0.013,0.71,0.015,0.01,0.0064,0,0,-4.9e+02,-0.0013,-0.0059,-5.7e-06,0.011,0.004,-0.13,0.21,-5.1e-06,0.43,-0.00032,0.0007,5.5e-05,0,0,-4.9e+02,0.00011,9.6e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0064,0.00047,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19890000,0.71,0.00066,-0.013,0.71,0.015,0.012,0.0075,0,0,-4.9e+02,-0.0013,-0.0058,2.4e-06,0.011,0.0029,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00071,6.2e-05,0,0,-4.9e+02,0.00011,9.6e-05,0.036,0.015,0.018,0.01,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19990000,0.71,0.00063,-0.013,0.71,0.013,0.012,0.01,0,0,-4.9e+02,-0.0013,-0.0058,1.8e-05,0.012,0.0021,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00073,6.7e-05,0,0,-4.9e+02,0.0001,9.4e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.041,7.9e-07,1.3e-06,2.1e-06,0.0052,0.0062,0.00044,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +20090000,0.71,0.00066,-0.013,0.71,0.013,0.013,0.011,0,0,-4.9e+02,-0.0013,-0.0058,2.8e-05,0.012,0.0013,-0.13,0.21,-4.5e-06,0.43,-0.00032,0.00075,7.7e-05,0,0,-4.9e+02,0.00011,9.5e-05,0.036,0.014,0.018,0.01,0.041,0.043,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20190000,0.71,0.00069,-0.013,0.71,0.012,0.011,0.013,0,0,-4.9e+02,-0.0013,-0.0058,3.7e-05,0.012,0.001,-0.13,0.21,-4.5e-06,0.43,-0.00031,0.00075,7.6e-05,0,0,-4.9e+02,0.0001,9.3e-05,0.036,0.013,0.016,0.0098,0.038,0.039,0.041,7.6e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00042,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20290000,0.71,0.0007,-0.013,0.71,0.01,0.011,0.011,0,0,-4.9e+02,-0.0013,-0.0058,4e-05,0.012,0.00092,-0.13,0.21,-4.5e-06,0.43,-0.00032,0.00076,7.8e-05,0,0,-4.9e+02,0.0001,9.3e-05,0.036,0.014,0.018,0.0097,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20390000,0.71,0.00066,-0.013,0.7,0.0086,0.0091,0.013,0,0,-4.9e+02,-0.0013,-0.0058,4.4e-05,0.012,0.001,-0.13,0.21,-4.6e-06,0.43,-0.00031,0.00076,6.8e-05,0,0,-4.9e+02,0.0001,9.1e-05,0.036,0.013,0.016,0.0095,0.037,0.039,0.04,7.3e-07,1.1e-06,2e-06,0.0051,0.006,0.00039,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20490000,0.71,0.00071,-0.013,0.7,0.0087,0.009,0.013,0,0,-4.9e+02,-0.0013,-0.0058,4.1e-05,0.012,0.0013,-0.13,0.21,-4.6e-06,0.43,-0.00031,0.00075,6.6e-05,0,0,-4.9e+02,0.0001,9.1e-05,0.036,0.014,0.017,0.0094,0.041,0.043,0.04,7.2e-07,1.1e-06,2e-06,0.005,0.006,0.00038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20590000,0.71,0.00074,-0.013,0.7,0.0078,0.007,0.0099,0,0,-4.9e+02,-0.0013,-0.0058,4.2e-05,0.012,0.0018,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00074,6.6e-05,0,0,-4.9e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0092,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0059,0.00037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20690000,0.71,0.00077,-0.013,0.7,0.0085,0.007,0.011,0,0,-4.9e+02,-0.0013,-0.0058,4.5e-05,0.012,0.0016,-0.13,0.21,-4.7e-06,0.43,-0.00032,0.00075,6.7e-05,0,0,-4.9e+02,0.0001,8.9e-05,0.036,0.014,0.017,0.0092,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.005,0.0058,0.00036,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20790000,0.71,0.00081,-0.013,0.7,0.0063,0.0066,0.012,0,0,-4.9e+02,-0.0013,-0.0058,5e-05,0.013,0.0017,-0.13,0.21,-4.8e-06,0.43,-0.00032,0.00075,6.2e-05,0,0,-4.9e+02,9.8e-05,8.8e-05,0.036,0.013,0.016,0.009,0.037,0.039,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0058,0.00035,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20890000,0.71,0.00081,-0.013,0.7,0.0062,0.0062,0.011,0,0,-4.9e+02,-0.0013,-0.0058,5.8e-05,0.013,0.0013,-0.13,0.21,-4.8e-06,0.43,-0.00033,0.00077,6.7e-05,0,0,-4.9e+02,9.9e-05,8.8e-05,0.036,0.014,0.017,0.0089,0.04,0.043,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +20990000,0.71,0.00083,-0.013,0.7,0.0045,0.0039,0.011,0,0,-4.9e+02,-0.0013,-0.0058,6.2e-05,0.013,0.0015,-0.13,0.21,-4.8e-06,0.43,-0.00034,0.00077,6.4e-05,0,0,-4.9e+02,9.6e-05,8.6e-05,0.036,0.013,0.016,0.0087,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0049,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21090000,0.71,0.00081,-0.013,0.7,0.0054,0.0032,0.012,0,0,-4.9e+02,-0.0013,-0.0058,6.7e-05,0.013,0.0011,-0.13,0.21,-4.6e-06,0.43,-0.00033,0.00078,6.1e-05,0,0,-4.9e+02,9.7e-05,8.6e-05,0.036,0.014,0.017,0.0087,0.04,0.043,0.039,6.4e-07,9.9e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21190000,0.71,0.00082,-0.013,0.7,0.0057,0.0023,0.011,0,0,-4.9e+02,-0.0013,-0.0058,6.7e-05,0.013,0.0012,-0.13,0.21,-4.6e-06,0.43,-0.00033,0.00077,5.8e-05,0,0,-4.9e+02,9.5e-05,8.5e-05,0.036,0.013,0.016,0.0085,0.037,0.039,0.039,6.3e-07,9.5e-07,2e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21290000,0.71,0.0009,-0.013,0.7,0.005,0.0023,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.8e-05,0.013,0.00077,-0.13,0.21,-4.6e-06,0.43,-0.00034,0.0008,6.2e-05,0,0,-4.9e+02,9.5e-05,8.5e-05,0.036,0.014,0.017,0.0084,0.04,0.043,0.038,6.2e-07,9.5e-07,1.9e-06,0.0048,0.0055,0.00031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21390000,0.71,0.00088,-0.013,0.7,0.004,0.00034,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.3e-05,0.013,0.00093,-0.13,0.21,-4.8e-06,0.43,-0.00033,0.00079,6.2e-05,0,0,-4.9e+02,9.3e-05,8.3e-05,0.036,0.013,0.016,0.0083,0.037,0.039,0.038,6e-07,9.1e-07,1.9e-06,0.0047,0.0055,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21490000,0.71,0.00088,-0.013,0.7,0.0045,0.00077,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.7e-05,0.013,0.00058,-0.13,0.21,-4.7e-06,0.43,-0.00032,0.00079,6.7e-05,0,0,-4.9e+02,9.4e-05,8.3e-05,0.036,0.014,0.017,0.0082,0.04,0.043,0.038,6e-07,9.1e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21590000,0.71,0.00087,-0.013,0.7,0.0034,0.0013,0.012,0,0,-4.9e+02,-0.0013,-0.0058,7.6e-05,0.013,0.00061,-0.13,0.21,-4.9e-06,0.43,-0.00032,0.00079,6.4e-05,0,0,-4.9e+02,9.1e-05,8.2e-05,0.036,0.013,0.015,0.0081,0.037,0.039,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0054,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21690000,0.71,0.00084,-0.013,0.7,0.005,0.0016,0.014,0,0,-4.9e+02,-0.0013,-0.0058,8e-05,0.013,0.0002,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00079,6.4e-05,0,0,-4.9e+02,9.2e-05,8.2e-05,0.036,0.013,0.017,0.0081,0.04,0.042,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0053,0.00028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21790000,0.71,0.00084,-0.013,0.7,0.0031,0.0037,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7e-05,0.013,0.00038,-0.13,0.21,-5.4e-06,0.43,-0.00033,0.00079,6.6e-05,0,0,-4.9e+02,9e-05,8.1e-05,0.036,0.012,0.015,0.0079,0.037,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0053,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21890000,0.71,0.00083,-0.013,0.7,0.0038,0.0043,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.1e-05,0.013,0.00029,-0.13,0.21,-5.3e-06,0.43,-0.00033,0.00079,6.4e-05,0,0,-4.9e+02,9.1e-05,8.1e-05,0.036,0.013,0.016,0.0079,0.04,0.042,0.037,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0053,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21990000,0.71,0.00085,-0.013,0.7,0.0026,0.005,0.014,0,0,-4.9e+02,-0.0013,-0.0058,6.8e-05,0.014,0.00012,-0.13,0.21,-5.7e-06,0.43,-0.00034,0.00079,6.5e-05,0,0,-4.9e+02,8.9e-05,7.9e-05,0.036,0.012,0.015,0.0077,0.036,0.038,0.037,5.5e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22090000,0.71,0.00088,-0.013,0.7,0.0025,0.0065,0.012,0,0,-4.9e+02,-0.0013,-0.0058,6.8e-05,0.014,0.00017,-0.13,0.21,-5.7e-06,0.43,-0.00034,0.00079,6.5e-05,0,0,-4.9e+02,8.9e-05,8e-05,0.036,0.013,0.016,0.0077,0.04,0.042,0.037,5.4e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22190000,0.71,0.00085,-0.013,0.7,0.002,0.0065,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.4e-05,0.014,0.00023,-0.13,0.21,-5.5e-06,0.43,-0.00035,0.0008,5.5e-05,0,0,-4.9e+02,8.7e-05,7.8e-05,0.036,0.012,0.015,0.0076,0.036,0.038,0.037,5.3e-07,7.7e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22290000,0.71,0.00088,-0.013,0.7,0.0013,0.0062,0.013,0,0,-4.9e+02,-0.0013,-0.0058,7.2e-05,0.014,0.00029,-0.13,0.21,-5.5e-06,0.43,-0.00035,0.00079,5.6e-05,0,0,-4.9e+02,8.8e-05,7.8e-05,0.036,0.013,0.016,0.0075,0.04,0.042,0.037,5.2e-07,7.7e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22390000,0.71,0.0009,-0.013,0.7,-0.00098,0.006,0.015,0,0,-4.9e+02,-0.0013,-0.0058,7.9e-05,0.014,0.00049,-0.13,0.21,-5.5e-06,0.43,-0.00035,0.0008,5.7e-05,0,0,-4.9e+02,8.6e-05,7.7e-05,0.036,0.012,0.015,0.0074,0.036,0.038,0.037,5.1e-07,7.4e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22490000,0.71,0.00094,-0.013,0.7,-0.0021,0.0068,0.016,0,0,-4.9e+02,-0.0013,-0.0058,8e-05,0.014,0.00063,-0.13,0.21,-5.4e-06,0.43,-0.00036,0.0008,5.5e-05,0,0,-4.9e+02,8.7e-05,7.7e-05,0.036,0.013,0.016,0.0074,0.039,0.042,0.037,5.1e-07,7.4e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22590000,0.71,0.00096,-0.013,0.7,-0.0038,0.0062,0.015,0,0,-4.9e+02,-0.0014,-0.0058,8.3e-05,0.015,0.0008,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.00081,5.2e-05,0,0,-4.9e+02,8.5e-05,7.6e-05,0.036,0.012,0.015,0.0073,0.036,0.038,0.036,5e-07,7.1e-07,1.8e-06,0.0044,0.005,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22690000,0.71,0.001,-0.013,0.7,-0.0051,0.0076,0.016,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.015,0.00069,-0.13,0.21,-5.3e-06,0.43,-0.00039,0.00082,5.1e-05,0,0,-4.9e+02,8.5e-05,7.6e-05,0.036,0.013,0.016,0.0073,0.039,0.042,0.036,4.9e-07,7.1e-07,1.8e-06,0.0044,0.005,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22790000,0.71,0.001,-0.013,0.7,-0.0071,0.0065,0.017,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.015,0.0015,-0.13,0.21,-5.5e-06,0.43,-0.00038,0.00081,5.7e-05,0,0,-4.9e+02,8.3e-05,7.5e-05,0.036,0.012,0.015,0.0071,0.036,0.038,0.036,4.8e-07,6.8e-07,1.8e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22890000,0.71,0.001,-0.013,0.7,-0.0075,0.0074,0.019,0,0,-4.9e+02,-0.0014,-0.0058,7.8e-05,0.015,0.0013,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.0008,5.3e-05,0,0,-4.9e+02,8.4e-05,7.5e-05,0.036,0.013,0.016,0.0071,0.039,0.042,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22990000,0.71,0.00097,-0.013,0.7,-0.0076,0.0065,0.02,0,0,-4.9e+02,-0.0014,-0.0058,8.8e-05,0.015,0.0012,-0.13,0.21,-5.1e-06,0.43,-0.00038,0.00081,5.1e-05,0,0,-4.9e+02,8.2e-05,7.4e-05,0.036,0.012,0.015,0.007,0.036,0.038,0.036,4.7e-07,6.6e-07,1.7e-06,0.0044,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23090000,0.71,0.00092,-0.013,0.7,-0.008,0.0063,0.02,0,0,-4.9e+02,-0.0014,-0.0058,7.9e-05,0.015,0.0015,-0.13,0.21,-5.3e-06,0.43,-0.00038,0.00079,4.8e-05,0,0,-4.9e+02,8.3e-05,7.4e-05,0.036,0.013,0.016,0.007,0.039,0.042,0.036,4.7e-07,6.6e-07,1.7e-06,0.0044,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23190000,0.71,0.00098,-0.013,0.7,-0.0093,0.0044,0.022,0,0,-4.9e+02,-0.0014,-0.0058,8.2e-05,0.015,0.0017,-0.13,0.21,-5.3e-06,0.43,-0.00037,0.00079,4e-05,0,0,-4.9e+02,8.1e-05,7.3e-05,0.036,0.012,0.014,0.0069,0.036,0.038,0.035,4.6e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 +23290000,0.71,0.0009,-0.013,0.7,-0.0092,0.0038,0.022,0,0,-4.9e+02,-0.0014,-0.0058,8.4e-05,0.015,0.0015,-0.13,0.21,-5.2e-06,0.43,-0.00037,0.00079,3.9e-05,0,0,-4.9e+02,8.2e-05,7.3e-05,0.036,0.013,0.016,0.0069,0.039,0.042,0.036,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 +23390000,0.71,0.00095,-0.013,0.7,-0.0095,0.0026,0.02,0,0,-4.9e+02,-0.0014,-0.0058,8.6e-05,0.014,0.0015,-0.13,0.21,-5.3e-06,0.43,-0.00035,0.00078,4e-05,0,0,-4.9e+02,8e-05,7.2e-05,0.036,0.012,0.014,0.0068,0.036,0.038,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 +23490000,0.71,0.0033,-0.011,0.7,-0.016,0.0029,-0.013,0,0,-4.9e+02,-0.0014,-0.0058,9.2e-05,0.014,0.0013,-0.13,0.21,-5.3e-06,0.43,-0.00034,0.00081,6.5e-05,0,0,-4.9e+02,8.1e-05,7.2e-05,0.036,0.013,0.015,0.0068,0.039,0.042,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 +23590000,0.71,0.0086,-0.0027,0.7,-0.027,0.0029,-0.045,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.014,0.0013,-0.13,0.21,-5.2e-06,0.43,-0.00034,0.00087,0.00013,0,0,-4.9e+02,7.9e-05,7.1e-05,0.036,0.012,0.014,0.0067,0.036,0.038,0.035,4.3e-07,5.9e-07,1.6e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23690000,0.71,0.0082,0.003,0.71,-0.058,-0.0049,-0.095,0,0,-4.9e+02,-0.0014,-0.0058,8.9e-05,0.014,0.0013,-0.13,0.21,-5.2e-06,0.43,-0.00034,0.00081,0.0001,0,0,-4.9e+02,8e-05,7.1e-05,0.036,0.013,0.015,0.0067,0.039,0.042,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0047,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23790000,0.71,0.0053,-0.00025,0.71,-0.083,-0.017,-0.15,0,0,-4.9e+02,-0.0013,-0.0058,9.1e-05,0.014,0.00079,-0.13,0.21,-4.5e-06,0.43,-0.0004,0.0008,0.00045,0,0,-4.9e+02,7.8e-05,7e-05,0.036,0.012,0.014,0.0066,0.036,0.038,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23890000,0.71,0.0026,-0.0063,0.71,-0.1,-0.025,-0.2,0,0,-4.9e+02,-0.0013,-0.0058,9e-05,0.014,0.00093,-0.13,0.21,-4.4e-06,0.43,-0.00042,0.00086,0.00036,0,0,-4.9e+02,7.9e-05,7e-05,0.036,0.013,0.016,0.0066,0.039,0.042,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23990000,0.71,0.0013,-0.011,0.71,-0.1,-0.029,-0.26,0,0,-4.9e+02,-0.0013,-0.0058,9.6e-05,0.014,0.00094,-0.13,0.21,-4e-06,0.43,-0.0004,0.00086,0.00034,0,0,-4.9e+02,7.7e-05,6.9e-05,0.036,0.012,0.015,0.0065,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0046,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24090000,0.71,0.0025,-0.0096,0.71,-0.1,-0.028,-0.3,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.014,0.00064,-0.13,0.21,-3.6e-06,0.43,-0.00042,0.00083,0.00037,0,0,-4.9e+02,7.8e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0046,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24190000,0.71,0.0036,-0.0073,0.71,-0.11,-0.03,-0.35,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.014,0.00052,-0.13,0.21,-2.9e-06,0.43,-0.00043,0.00086,0.00037,0,0,-4.9e+02,7.6e-05,6.8e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,4e-07,5.4e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24290000,0.71,0.0041,-0.0065,0.71,-0.12,-0.033,-0.41,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.013,0.00049,-0.13,0.21,-2.6e-06,0.43,-0.00046,0.0009,0.00044,0,0,-4.9e+02,7.7e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4e-07,5.4e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24390000,0.71,0.0042,-0.0067,0.71,-0.13,-0.041,-0.46,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.013,0.0011,-0.13,0.21,2.4e-07,0.43,-0.00034,0.00095,0.00043,0,0,-4.9e+02,7.5e-05,6.7e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24490000,0.71,0.0051,-0.0025,0.71,-0.14,-0.046,-0.51,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.013,0.0011,-0.13,0.21,2.4e-07,0.43,-0.00034,0.00096,0.00042,0,0,-4.9e+02,7.6e-05,6.8e-05,0.036,0.013,0.016,0.0064,0.039,0.042,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24590000,0.71,0.0055,0.0012,0.71,-0.16,-0.057,-0.56,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.013,0.0011,-0.13,0.21,1.3e-06,0.43,1.3e-05,0.00061,0.00037,0,0,-4.9e+02,7.4e-05,6.7e-05,0.036,0.012,0.015,0.0063,0.036,0.038,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24690000,0.71,0.0056,0.0021,0.71,-0.18,-0.07,-0.64,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.013,0.00096,-0.13,0.21,2.3e-06,0.43,-3.2e-05,0.00065,0.00056,0,0,-4.9e+02,7.5e-05,6.7e-05,0.036,0.013,0.016,0.0063,0.039,0.042,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24790000,0.71,0.0053,0.00083,0.71,-0.2,-0.084,-0.73,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.012,0.001,-0.13,0.21,1.6e-06,0.43,1.7e-07,0.00062,0.00032,0,0,-4.9e+02,7.3e-05,6.6e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24890000,0.71,0.0071,0.0025,0.71,-0.22,-0.095,-0.75,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.012,0.0011,-0.13,0.21,2.4e-06,0.43,-0.00011,0.00077,0.00034,0,0,-4.9e+02,7.4e-05,6.6e-05,0.036,0.013,0.016,0.0062,0.039,0.042,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24990000,0.71,0.0089,0.0043,0.71,-0.24,-0.1,-0.81,0,0,-4.9e+02,-0.0013,-0.0058,0.00011,0.012,0.00071,-0.13,0.21,1.8e-06,0.43,-0.00019,0.00087,-3.6e-06,0,0,-4.9e+02,7.2e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.8e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25090000,0.71,0.0092,0.0037,0.71,-0.27,-0.11,-0.86,0,0,-4.9e+02,-0.0013,-0.0058,0.0001,0.012,0.0008,-0.13,0.21,1.4e-06,0.43,-0.0002,0.00088,-3.9e-05,0,0,-4.9e+02,7.3e-05,6.5e-05,0.036,0.013,0.017,0.0062,0.039,0.042,0.033,3.7e-07,4.8e-07,1.5e-06,0.0041,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25190000,0.71,0.0087,0.0023,0.71,-0.3,-0.13,-0.91,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.011,0.0011,-0.13,0.21,6.8e-06,0.43,5e-05,0.00085,9.7e-05,0,0,-4.9e+02,7.2e-05,6.4e-05,0.035,0.012,0.016,0.0061,0.036,0.038,0.033,3.6e-07,4.6e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25290000,0.71,0.011,0.0091,0.71,-0.33,-0.14,-0.96,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.011,0.0011,-0.13,0.21,6.6e-06,0.43,7.6e-05,0.0008,0.0001,0,0,-4.9e+02,7.2e-05,6.5e-05,0.035,0.013,0.017,0.0061,0.039,0.042,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25390000,0.71,0.012,0.016,0.71,-0.36,-0.16,-1,0,0,-4.9e+02,-0.0013,-0.0058,0.00013,0.011,0.00086,-0.13,0.21,1e-05,0.43,0.00048,0.00048,0.00014,0,0,-4.9e+02,7.1e-05,6.3e-05,0.035,0.012,0.016,0.006,0.036,0.038,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25490000,0.71,0.012,0.017,0.71,-0.41,-0.18,-1.1,0,0,-4.9e+02,-0.0013,-0.0058,0.00014,0.011,0.00074,-0.13,0.21,9.2e-06,0.43,0.00065,0.00016,0.00033,0,0,-4.9e+02,7.2e-05,6.4e-05,0.035,0.013,0.018,0.006,0.039,0.042,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25590000,0.71,0.012,0.015,0.71,-0.45,-0.21,-1.1,0,0,-4.9e+02,-0.0012,-0.0058,0.00015,0.0099,0.0011,-0.13,0.21,1.5e-05,0.43,0.00095,0.00016,0.00034,0,0,-4.9e+02,7.1e-05,6.3e-05,0.034,0.012,0.018,0.006,0.036,0.038,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25690000,0.71,0.015,0.022,0.71,-0.49,-0.23,-1.2,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.0099,0.0011,-0.13,0.21,1.6e-05,0.43,0.00094,0.00018,0.00042,0,0,-4.9e+02,7.1e-05,6.3e-05,0.034,0.013,0.02,0.006,0.039,0.042,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0014,0.0012,0.0011,1,1,0.01 +25790000,0.71,0.018,0.028,0.71,-0.54,-0.26,-1.2,0,0,-4.9e+02,-0.0012,-0.0058,0.00016,0.0092,0.00041,-0.13,0.21,1.9e-05,0.43,0.0013,-6.7e-05,-3e-05,0,0,-4.9e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.0059,0.036,0.038,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 +25890000,0.71,0.018,0.028,0.71,-0.62,-0.29,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00017,0.0094,0.00034,-0.13,0.21,2.1e-05,0.43,0.0014,7.9e-07,-9.6e-05,0,0,-4.9e+02,7.1e-05,6.3e-05,0.033,0.014,0.022,0.006,0.039,0.042,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 +25990000,0.7,0.017,0.025,0.71,-0.67,-0.32,-1.3,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0085,0.00068,-0.13,0.21,2.8e-05,0.43,0.0023,-0.00056,-0.00055,0,0,-4.9e+02,7e-05,6.2e-05,0.032,0.013,0.021,0.0059,0.036,0.039,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 +26090000,0.7,0.022,0.035,0.71,-0.74,-0.35,-1.3,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0086,0.00085,-0.13,0.21,2.4e-05,0.43,0.0024,-0.00048,-0.0012,0,0,-4.9e+02,7.1e-05,6.2e-05,0.032,0.014,0.024,0.0059,0.039,0.043,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 +26190000,0.7,0.024,0.045,0.71,-0.79,-0.39,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00018,0.0075,-0.00028,-0.13,0.21,3.8e-05,0.43,0.0023,0.00041,-0.0014,0,0,-4.9e+02,7.1e-05,6.1e-05,0.03,0.014,0.024,0.0058,0.036,0.039,0.032,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.001,0.0013,0.001,0.001,1,1,0.01 +26290000,0.7,0.025,0.047,0.71,-0.89,-0.43,-1.3,0,0,-4.9e+02,-0.0012,-0.0058,0.00018,0.0075,-0.00026,-0.13,0.21,3.7e-05,0.43,0.0023,0.00028,-0.0014,0,0,-4.9e+02,7.1e-05,6.2e-05,0.03,0.015,0.028,0.0059,0.039,0.043,0.033,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.00099,0.0013,0.001,0.00099,1,1,0.01 +26390000,0.7,0.024,0.044,0.71,-0.96,-0.49,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00021,0.0066,0.00051,-0.13,0.21,4.4e-05,0.44,0.0036,-0.00018,-0.0024,0,0,-4.9e+02,7.1e-05,6.1e-05,0.028,0.014,0.027,0.0058,0.036,0.039,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0042,0.00014,0.00096,3.9e-05,0.00096,0.0012,0.00096,0.00095,1,1,0.01 +26490000,0.7,0.031,0.06,0.71,-1.1,-0.53,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.0002,0.0066,0.00051,-0.13,0.21,3.8e-05,0.44,0.0039,-0.00099,-0.0026,0,0,-4.9e+02,7.2e-05,6.1e-05,0.028,0.016,0.031,0.0058,0.039,0.044,0.032,3.3e-07,4.1e-07,1.3e-06,0.004,0.0042,0.00014,0.00092,3.9e-05,0.00092,0.0012,0.00092,0.00091,1,1,0.01 +26590000,0.7,0.037,0.076,0.71,-1.2,-0.59,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00019,0.005,-0.00049,-0.13,0.21,3.7e-05,0.44,0.0041,-0.00065,-0.0048,0,0,-4.9e+02,7.2e-05,6e-05,0.025,0.015,0.031,0.0058,0.036,0.04,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00087,3.9e-05,0.00086,0.001,0.00087,0.00086,1,1,0.01 +26690000,0.7,0.039,0.079,0.71,-1.3,-0.65,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00019,0.0051,-0.00058,-0.13,0.21,4.3e-05,0.44,0.0039,-0.00013,-0.004,0,0,-4.9e+02,7.2e-05,6.1e-05,0.025,0.017,0.038,0.0058,0.04,0.045,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00081,3.9e-05,0.0008,0.001,0.00081,0.00079,1,1,0.01 +26790000,0.7,0.036,0.073,0.71,-1.4,-0.74,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00022,0.0034,0.00028,-0.13,0.21,8.2e-05,0.44,0.0054,0.00061,-0.0037,0,0,-4.9e+02,7.3e-05,6e-05,0.022,0.016,0.036,0.0057,0.036,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00076,3.9e-05,0.00075,0.00092,0.00076,0.00074,1,1,0.01 +26890000,0.7,0.045,0.095,0.71,-1.6,-0.8,-1.3,0,0,-4.9e+02,-0.0011,-0.0059,0.00022,0.0035,0.00026,-0.13,0.21,8.7e-05,0.44,0.0053,0.0012,-0.0041,0,0,-4.9e+02,7.3e-05,6e-05,0.022,0.018,0.043,0.0058,0.04,0.046,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00072,3.9e-05,0.0007,0.00091,0.00072,0.0007,1,1,0.01 +26990000,0.7,0.051,0.12,0.71,-1.7,-0.89,-1.3,0,0,-4.9e+02,-0.00099,-0.0059,0.00022,0.0015,-0.0017,-0.13,0.21,0.00012,0.44,0.006,0.0034,-0.0056,0,0,-4.9e+02,7.4e-05,6e-05,0.019,0.017,0.042,0.0057,0.037,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00065,3.9e-05,0.00063,0.00079,0.00065,0.00062,1,1,0.01 +27090000,0.7,0.052,0.12,0.71,-1.9,-0.98,-1.3,0,0,-4.9e+02,-0.00098,-0.0059,0.00022,0.0015,-0.0016,-0.13,0.21,0.00012,0.44,0.006,0.0035,-0.0051,0,0,-4.9e+02,7.4e-05,6e-05,0.019,0.02,0.052,0.0057,0.04,0.048,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00059,3.9e-05,0.00056,0.00078,0.0006,0.00056,1,1,0.01 +27190000,0.7,0.05,0.11,0.7,-2.1,-1,-1.2,0,0,-4.9e+02,-0.00097,-0.0059,0.00022,0.00037,-0.0018,-0.13,0.21,4.5e-05,0.44,0.002,0.0027,-0.0049,0,0,-4.9e+02,7.5e-05,6e-05,0.016,0.02,0.051,0.0057,0.043,0.05,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00055,3.9e-05,0.00051,0.00066,0.00055,0.00051,1,1,0.01 +27290000,0.71,0.044,0.095,0.7,-2.3,-1.1,-1.2,0,0,-4.9e+02,-0.00097,-0.0059,0.00023,0.00042,-0.0018,-0.13,0.21,5.2e-05,0.44,0.0019,0.0034,-0.0049,0,0,-4.9e+02,7.6e-05,6.1e-05,0.016,0.022,0.059,0.0057,0.047,0.057,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00052,3.9e-05,0.00048,0.00066,0.00052,0.00048,1,1,0.01 +27390000,0.71,0.038,0.079,0.7,-2.4,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0058,0.00021,-0.00081,-0.0036,-0.13,0.21,9.9e-06,0.44,-0.0006,0.0031,-0.0063,0,0,-4.9e+02,7.6e-05,6e-05,0.013,0.021,0.052,0.0057,0.049,0.059,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00049,3.9e-05,0.00046,0.00055,0.00049,0.00046,1,1,0.01 +27490000,0.71,0.032,0.064,0.7,-2.5,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00022,-0.00074,-0.0035,-0.13,0.21,1.5e-05,0.44,-0.00068,0.0032,-0.0067,0,0,-4.9e+02,7.7e-05,6.1e-05,0.013,0.023,0.056,0.0057,0.054,0.067,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00048,3.9e-05,0.00045,0.00055,0.00048,0.00044,1,1,0.01 +27590000,0.72,0.028,0.051,0.69,-2.6,-1.1,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00023,-0.0014,-0.0029,-0.12,0.21,-4.1e-05,0.44,-0.0033,0.0027,-0.0065,0,0,-4.9e+02,7.7e-05,6.1e-05,0.011,0.021,0.047,0.0057,0.056,0.068,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00044,1,1,0.01 +27690000,0.72,0.027,0.05,0.69,-2.6,-1.2,-1.2,0,0,-4.9e+02,-0.00092,-0.0059,0.00022,-0.0014,-0.0028,-0.12,0.21,-3.6e-05,0.44,-0.0034,0.0026,-0.0067,0,0,-4.9e+02,7.8e-05,6.1e-05,0.011,0.022,0.049,0.0057,0.062,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00043,1,1,0.01 +27790000,0.72,0.027,0.051,0.69,-2.6,-1.2,-1.2,0,0,-4.9e+02,-0.00091,-0.0059,0.00022,-0.0019,-0.0026,-0.12,0.21,-6.4e-05,0.44,-0.0052,0.002,-0.0072,0,0,-4.9e+02,7.9e-05,6.1e-05,0.0097,0.02,0.042,0.0056,0.064,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00045,3.9e-05,0.00043,0.00041,0.00045,0.00043,1,1,0.01 +27890000,0.72,0.027,0.049,0.69,-2.7,-1.2,-1.2,0,0,-4.9e+02,-0.00091,-0.0059,0.00022,-0.002,-0.0026,-0.12,0.21,-6.5e-05,0.44,-0.0051,0.002,-0.0072,0,0,-4.9e+02,7.9e-05,6.1e-05,0.0097,0.021,0.043,0.0057,0.07,0.087,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00044,3.9e-05,0.00043,0.00041,0.00044,0.00042,1,1,0.01 +27990000,0.72,0.026,0.046,0.69,-2.7,-1.2,-1.2,0,0,-4.9e+02,-0.00093,-0.0059,0.00024,-0.0018,-0.0017,-0.12,0.21,-8.1e-05,0.44,-0.0065,0.0014,-0.0071,0,0,-4.9e+02,8e-05,6.1e-05,0.0086,0.02,0.038,0.0056,0.072,0.087,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00043,3.9e-05,0.00042,0.00037,0.00043,0.00042,1,1,0.01 +28090000,0.72,0.032,0.059,0.69,-2.8,-1.2,-1.2,0,0,-4.9e+02,-0.00093,-0.0059,0.00023,-0.0019,-0.0015,-0.12,0.21,-8e-05,0.44,-0.0066,0.0013,-0.0072,0,0,-4.9e+02,8.1e-05,6.1e-05,0.0086,0.021,0.039,0.0057,0.078,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00042,3.9e-05,0.00042,0.00036,0.00042,0.00041,1,1,0.01 +28190000,0.72,0.037,0.072,0.69,-2.8,-1.2,-0.94,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.002,-0.001,-0.12,0.21,-9.9e-05,0.44,-0.0074,0.00088,-0.0071,0,0,-4.9e+02,8.1e-05,6.1e-05,0.0079,0.02,0.034,0.0056,0.08,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00041,3.9e-05,0.00041,0.00033,0.00041,0.00041,1,1,0.01 +28290000,0.72,0.029,0.055,0.69,-2.8,-1.2,-0.078,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0021,-0.00091,-0.12,0.21,-0.0001,0.44,-0.0075,0.0013,-0.0069,0,0,-4.9e+02,8.2e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.087,0.11,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28390000,0.73,0.012,0.024,0.69,-2.8,-1.2,0.78,0,0,-4.9e+02,-0.00094,-0.0059,0.00023,-0.002,-0.00063,-0.12,0.21,-8.9e-05,0.44,-0.0076,0.0013,-0.007,0,0,-4.9e+02,8.3e-05,6.2e-05,0.0079,0.02,0.035,0.0057,0.094,0.12,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28490000,0.73,0.0028,0.0059,0.69,-2.8,-1.2,1.1,0,0,-4.9e+02,-0.00095,-0.0059,0.00023,-0.0016,-0.00036,-0.12,0.21,-7e-05,0.44,-0.0077,0.0014,-0.0069,0,0,-4.9e+02,8.4e-05,6.2e-05,0.0079,0.021,0.035,0.0057,0.1,0.13,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28590000,0.73,0.00089,0.0024,0.69,-2.7,-1.2,0.97,0,0,-4.9e+02,-0.00094,-0.0059,0.00024,-0.0017,-0.00031,-0.12,0.21,-7.3e-05,0.44,-0.0076,0.0015,-0.0069,0,0,-4.9e+02,8.4e-05,6.2e-05,0.0079,0.021,0.033,0.0057,0.11,0.14,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28690000,0.73,0.00019,0.0015,0.69,-2.6,-1.2,0.98,0,0,-4.9e+02,-0.00095,-0.0059,0.00023,-0.0014,4.3e-05,-0.12,0.21,-5.6e-05,0.44,-0.0077,0.0014,-0.0068,0,0,-4.9e+02,8.5e-05,6.2e-05,0.0079,0.022,0.033,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.00039,0.0004,1,1,0.01 +28790000,0.73,-1.2e-05,0.0014,0.69,-2.6,-1.2,0.98,0,0,-4.9e+02,-0.00098,-0.0059,0.00024,-0.00092,0.00026,-0.12,0.21,-9.6e-05,0.44,-0.0092,0.0006,-0.006,0,0,-4.9e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28890000,0.73,-2.3e-06,0.0016,0.69,-2.5,-1.2,0.97,0,0,-4.9e+02,-0.00099,-0.0059,0.00024,-0.00064,0.00058,-0.12,0.21,-8e-05,0.44,-0.0093,0.00056,-0.0059,0,0,-4.9e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.13,0.16,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28990000,0.73,0.00035,0.0022,0.68,-2.5,-1.1,0.97,0,0,-4.9e+02,-0.001,-0.0059,0.00025,0.00066,0.001,-0.12,0.21,-0.00011,0.44,-0.011,-0.00036,-0.0047,0,0,-4.9e+02,8.7e-05,6.2e-05,0.0073,0.02,0.025,0.0056,0.13,0.16,0.032,3e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.0003,0.00039,0.00039,1,1,0.01 +29090000,0.73,0.00052,0.0026,0.68,-2.4,-1.1,0.96,0,0,-4.9e+02,-0.001,-0.0059,0.00025,0.00085,0.0014,-0.12,0.21,-9.7e-05,0.44,-0.011,-0.00042,-0.0046,0,0,-4.9e+02,8.7e-05,6.2e-05,0.0073,0.021,0.025,0.0057,0.14,0.17,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29190000,0.73,0.00076,0.003,0.68,-2.4,-1.1,0.96,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.0012,0.0014,-0.12,0.21,-0.00013,0.44,-0.011,-0.00065,-0.0041,0,0,-4.9e+02,8.8e-05,6.1e-05,0.0072,0.02,0.023,0.0056,0.14,0.17,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29290000,0.73,0.0011,0.0038,0.68,-2.3,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.0013,0.0019,-0.12,0.21,-0.00012,0.44,-0.011,-0.00072,-0.0041,0,0,-4.9e+02,8.8e-05,6.2e-05,0.0072,0.021,0.024,0.0056,0.14,0.18,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29390000,0.73,0.0017,0.0054,0.68,-2.3,-1.1,0.99,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.002,0.0024,-0.12,0.21,-0.00016,0.44,-0.012,-0.0014,-0.0033,0,0,-4.9e+02,8.8e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.18,0.031,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 +29490000,0.73,0.0022,0.0064,0.68,-2.3,-1.1,0.99,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.002,0.0026,-0.12,0.21,-0.00015,0.44,-0.012,-0.0014,-0.0033,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.15,0.19,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 +29590000,0.73,0.0027,0.0075,0.68,-2.2,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00026,0.0026,0.0026,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.19,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00038,1,1,0.01 +29690000,0.73,0.003,0.0081,0.68,-2.2,-1.1,0.98,0,0,-4.9e+02,-0.0011,-0.0059,0.00025,0.0026,0.003,-0.12,0.21,-0.00016,0.44,-0.012,-0.0017,-0.0029,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29790000,0.73,0.0034,0.0085,0.68,-2.2,-1.1,0.96,0,0,-4.9e+02,-0.0012,-0.0059,0.00025,0.0036,0.0028,-0.12,0.21,-0.00018,0.44,-0.013,-0.0019,-0.0022,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29890000,0.73,0.0034,0.0087,0.68,-2.1,-1.1,0.95,0,0,-4.9e+02,-0.0012,-0.0059,0.00024,0.0033,0.0033,-0.12,0.21,-0.00018,0.44,-0.013,-0.002,-0.0023,0,0,-4.9e+02,9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.17,0.21,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29990000,0.73,0.0036,0.0087,0.68,-2.1,-1.1,0.94,0,0,-4.9e+02,-0.0012,-0.0059,0.00022,0.0038,0.0029,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-4.9e+02,8.9e-05,6e-05,0.0071,0.02,0.024,0.0056,0.17,0.21,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +30090000,0.73,0.0035,0.0086,0.68,-2.1,-1.1,0.93,0,0,-4.9e+02,-0.0012,-0.0059,0.00022,0.0035,0.0033,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-4.9e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.18,0.22,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00028,0.00037,0.00038,1,1,0.01 +30190000,0.73,0.0036,0.0084,0.68,-2.1,-1.1,0.91,0,0,-4.9e+02,-0.0012,-0.0059,0.00021,0.0043,0.0027,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-4.9e+02,8.8e-05,6e-05,0.007,0.02,0.025,0.0055,0.18,0.22,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00037,0.00038,1,1,0.01 +30290000,0.73,0.0035,0.0081,0.68,-2,-1.1,0.9,0,0,-4.9e+02,-0.0012,-0.0059,0.00021,0.0041,0.0029,-0.12,0.21,-0.00023,0.44,-0.013,-0.0024,-0.0016,0,0,-4.9e+02,8.9e-05,6.1e-05,0.007,0.021,0.026,0.0056,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30390000,0.73,0.0035,0.0079,0.68,-2,-1.1,0.89,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0049,0.0028,-0.12,0.21,-0.00022,0.43,-0.013,-0.0025,-0.0014,0,0,-4.9e+02,8.7e-05,6e-05,0.007,0.021,0.025,0.0055,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30490000,0.73,0.0034,0.0076,0.68,-2,-1.1,0.87,0,0,-4.9e+02,-0.0012,-0.0059,0.00019,0.0049,0.003,-0.12,0.21,-0.00022,0.43,-0.013,-0.0025,-0.0014,0,0,-4.9e+02,8.8e-05,6e-05,0.007,0.022,0.027,0.0056,0.2,0.24,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.8e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30590000,0.73,0.0034,0.0071,0.68,-1.9,-1,0.83,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0057,0.0026,-0.12,0.21,-0.00024,0.43,-0.012,-0.0025,-0.001,0,0,-4.9e+02,8.6e-05,6e-05,0.0069,0.021,0.026,0.0055,0.2,0.24,0.031,2.8e-07,3.5e-07,1.1e-06,0.0038,0.0039,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30690000,0.73,0.0031,0.0068,0.68,-1.9,-1,0.83,0,0,-4.9e+02,-0.0012,-0.0059,0.00018,0.0054,0.0029,-0.12,0.21,-0.00025,0.43,-0.012,-0.0025,-0.001,0,0,-4.9e+02,8.6e-05,6e-05,0.0069,0.022,0.028,0.0055,0.21,0.25,0.031,2.8e-07,3.5e-07,1.1e-06,0.0038,0.0039,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30790000,0.73,0.0031,0.0063,0.68,-1.9,-1,0.82,0,0,-4.9e+02,-0.0012,-0.0059,0.00014,0.0062,0.0023,-0.12,0.21,-0.00025,0.43,-0.012,-0.0026,-0.00077,0,0,-4.9e+02,8.4e-05,6e-05,0.0068,0.021,0.027,0.0055,0.21,0.25,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30890000,0.73,0.0029,0.0059,0.68,-1.9,-1,0.81,0,0,-4.9e+02,-0.0013,-0.0059,0.00015,0.0062,0.0026,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00075,0,0,-4.9e+02,8.5e-05,6e-05,0.0068,0.022,0.029,0.0055,0.22,0.26,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00038,1,1,0.01 +30990000,0.73,0.003,0.0052,0.68,-1.8,-1,0.8,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.0071,0.0021,-0.12,0.21,-0.00026,0.43,-0.012,-0.0027,-0.00041,0,0,-4.9e+02,8.3e-05,6e-05,0.0067,0.021,0.028,0.0055,0.22,0.26,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.5e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00038,1,1,0.01 +31090000,0.73,0.0027,0.0047,0.68,-1.8,-1,0.79,0,0,-4.9e+02,-0.0013,-0.0058,0.00012,0.0069,0.0025,-0.12,0.21,-0.00026,0.43,-0.012,-0.0027,-0.00041,0,0,-4.9e+02,8.3e-05,6e-05,0.0067,0.022,0.03,0.0055,0.23,0.27,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31190000,0.73,0.0026,0.0043,0.68,-1.8,-1,0.78,0,0,-4.9e+02,-0.0013,-0.0058,9.5e-05,0.0072,0.0024,-0.12,0.21,-0.00027,0.43,-0.011,-0.0028,-0.00024,0,0,-4.9e+02,8.1e-05,5.9e-05,0.0066,0.021,0.028,0.0055,0.23,0.27,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31290000,0.73,0.0023,0.0037,0.68,-1.8,-1,0.78,0,0,-4.9e+02,-0.0013,-0.0058,9.8e-05,0.0069,0.0028,-0.11,0.21,-0.00028,0.43,-0.011,-0.0027,-0.00027,0,0,-4.9e+02,8.2e-05,6e-05,0.0066,0.022,0.03,0.0055,0.24,0.28,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.3e-05,0.00036,3.8e-05,0.00038,0.00027,0.00035,0.00037,1,1,0.01 +31390000,0.73,0.0022,0.003,0.68,-1.7,-0.99,0.78,0,0,-4.9e+02,-0.0013,-0.0058,7.6e-05,0.0074,0.0026,-0.11,0.21,-0.00031,0.43,-0.011,-0.0028,-2e-05,0,0,-4.9e+02,7.9e-05,5.9e-05,0.0065,0.021,0.029,0.0054,0.24,0.28,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31490000,0.73,0.0019,0.0024,0.68,-1.7,-0.99,0.78,0,0,-4.9e+02,-0.0013,-0.0058,7.2e-05,0.0073,0.0032,-0.11,0.2,-0.0003,0.43,-0.011,-0.0029,1.8e-05,0,0,-4.9e+02,8e-05,5.9e-05,0.0065,0.022,0.031,0.0055,0.25,0.29,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31590000,0.73,0.002,0.0019,0.68,-1.7,-0.97,0.77,0,0,-4.9e+02,-0.0013,-0.0058,4.5e-05,0.0082,0.0028,-0.11,0.2,-0.00029,0.43,-0.01,-0.0029,0.00026,0,0,-4.9e+02,7.8e-05,5.9e-05,0.0063,0.021,0.029,0.0054,0.25,0.29,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31690000,0.73,0.0017,0.0012,0.68,-1.6,-0.97,0.78,0,0,-4.9e+02,-0.0013,-0.0058,4.7e-05,0.0079,0.0031,-0.11,0.2,-0.0003,0.43,-0.01,-0.0029,0.00022,0,0,-4.9e+02,7.8e-05,5.9e-05,0.0063,0.022,0.031,0.0054,0.26,0.3,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31790000,0.73,0.0015,0.0004,0.69,-1.6,-0.95,0.78,0,0,-4.9e+02,-0.0013,-0.0058,2.2e-05,0.0089,0.003,-0.11,0.2,-0.0003,0.43,-0.0098,-0.0029,0.00056,0,0,-4.9e+02,7.6e-05,5.9e-05,0.0062,0.021,0.029,0.0054,0.26,0.3,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +31890000,0.73,0.0013,-0.00032,0.69,-1.6,-0.95,0.78,0,0,-4.9e+02,-0.0013,-0.0058,2.3e-05,0.0088,0.0035,-0.11,0.2,-0.0003,0.43,-0.0099,-0.0029,0.00059,0,0,-4.9e+02,7.6e-05,5.9e-05,0.0062,0.022,0.031,0.0054,0.27,0.31,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +31990000,0.73,0.0012,-0.00093,0.69,-1.6,-0.93,0.77,0,0,-4.9e+02,-0.0013,-0.0058,-8.8e-06,0.0093,0.0034,-0.11,0.2,-0.0003,0.43,-0.0094,-0.003,0.00076,0,0,-4.9e+02,7.4e-05,5.8e-05,0.006,0.021,0.03,0.0054,0.27,0.31,0.031,2.6e-07,2.9e-07,9.8e-07,0.0037,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32090000,0.73,0.00083,-0.0017,0.69,-1.5,-0.93,0.78,0,0,-4.9e+02,-0.0013,-0.0058,-9.7e-06,0.0091,0.0039,-0.11,0.2,-0.00029,0.43,-0.0094,-0.003,0.00077,0,0,-4.9e+02,7.5e-05,5.9e-05,0.006,0.022,0.032,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.8e-07,0.0037,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32190000,0.73,0.00063,-0.0026,0.69,-1.5,-0.91,0.78,0,0,-4.9e+02,-0.0014,-0.0058,-4.4e-05,0.0096,0.0039,-0.11,0.2,-0.00031,0.43,-0.0089,-0.0031,0.001,0,0,-4.9e+02,7.3e-05,5.8e-05,0.0059,0.021,0.03,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.6e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32290000,0.73,0.00035,-0.0034,0.69,-1.5,-0.91,0.77,0,0,-4.9e+02,-0.0014,-0.0058,-4.3e-05,0.0094,0.0045,-0.11,0.2,-0.00031,0.43,-0.0089,-0.0031,0.001,0,0,-4.9e+02,7.3e-05,5.8e-05,0.0059,0.022,0.032,0.0054,0.29,0.33,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00035,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32390000,0.73,0.00026,-0.0041,0.69,-1.5,-0.89,0.77,0,0,-4.9e+02,-0.0014,-0.0058,-6.2e-05,0.0099,0.0044,-0.11,0.2,-0.0003,0.43,-0.0085,-0.0031,0.0012,0,0,-4.9e+02,7.1e-05,5.8e-05,0.0057,0.021,0.03,0.0054,0.29,0.33,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32490000,0.72,0.00011,-0.0044,0.69,-1.4,-0.88,0.78,0,0,-4.9e+02,-0.0014,-0.0058,-6e-05,0.0097,0.0048,-0.11,0.2,-0.0003,0.43,-0.0085,-0.0031,0.0011,0,0,-4.9e+02,7.2e-05,5.8e-05,0.0057,0.022,0.032,0.0054,0.3,0.34,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32590000,0.72,0.00016,-0.0047,0.69,-1.4,-0.87,0.78,0,0,-4.9e+02,-0.0014,-0.0057,-8.1e-05,0.01,0.0048,-0.11,0.2,-0.00031,0.43,-0.0081,-0.0031,0.0013,0,0,-4.9e+02,7e-05,5.8e-05,0.0056,0.021,0.03,0.0053,0.3,0.34,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32690000,0.72,0.00012,-0.0048,0.69,-1.4,-0.86,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-8.1e-05,0.01,0.0052,-0.11,0.2,-0.00031,0.43,-0.0081,-0.0031,0.0014,0,0,-4.9e+02,7e-05,5.8e-05,0.0056,0.022,0.032,0.0053,0.31,0.35,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32790000,0.72,0.00024,-0.0048,0.69,-1.3,-0.84,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.0001,0.01,0.0052,-0.11,0.2,-0.0003,0.43,-0.0077,-0.0031,0.0015,0,0,-4.9e+02,6.8e-05,5.7e-05,0.0054,0.022,0.03,0.0053,0.3,0.35,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32890000,0.72,0.00031,-0.0048,0.69,-1.3,-0.84,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.01,0.0058,-0.11,0.2,-0.0003,0.43,-0.0078,-0.0032,0.0016,0,0,-4.9e+02,6.9e-05,5.8e-05,0.0054,0.022,0.031,0.0053,0.32,0.36,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32990000,0.72,0.00053,-0.0049,0.69,-1.3,-0.82,0.77,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.011,0.0059,-0.11,0.2,-0.00031,0.43,-0.0073,-0.0032,0.0017,0,0,-4.9e+02,6.7e-05,5.7e-05,0.0052,0.021,0.029,0.0053,0.31,0.36,0.03,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +33090000,0.72,0.0005,-0.0049,0.69,-1.3,-0.82,0.76,0,0,-4.9e+02,-0.0014,-0.0057,-0.00011,0.011,0.0062,-0.11,0.2,-0.00031,0.43,-0.0073,-0.0032,0.0017,0,0,-4.9e+02,6.8e-05,5.7e-05,0.0053,0.022,0.031,0.0053,0.33,0.37,0.031,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +33190000,0.72,0.004,-0.0041,0.7,-1.2,-0.8,0.7,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.011,0.0061,-0.11,0.2,-0.00031,0.43,-0.0069,-0.0032,0.0017,0,0,-4.9e+02,6.6e-05,5.7e-05,0.0051,0.022,0.029,0.0053,0.32,0.37,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 +33290000,0.67,0.016,-0.0035,0.74,-1.2,-0.78,0.68,0,0,-4.9e+02,-0.0014,-0.0057,-0.00012,0.011,0.0064,-0.11,0.2,-0.00029,0.43,-0.0071,-0.0033,0.0016,0,0,-4.9e+02,6.6e-05,5.7e-05,0.0051,0.022,0.031,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0036,8.3e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 +33390000,0.56,0.014,-0.0038,0.83,-1.2,-0.77,0.88,0,0,-4.9e+02,-0.0014,-0.0057,-0.00013,0.011,0.0067,-0.11,0.2,-0.00035,0.43,-0.0064,-0.0032,0.0018,0,0,-4.9e+02,6.5e-05,5.6e-05,0.0047,0.021,0.028,0.0053,0.33,0.38,0.031,2.4e-07,2.6e-07,8.3e-07,0.0036,0.0035,8.3e-05,0.00032,3.8e-05,0.00036,0.00021,0.00032,0.00036,1,1,0.01 +33490000,0.43,0.007,-0.0013,0.9,-1.2,-0.76,0.89,0,0,-4.9e+02,-0.0014,-0.0057,-0.00015,0.011,0.0068,-0.11,0.21,-0.00044,0.43,-0.0059,-0.002,0.0018,0,0,-4.9e+02,6.5e-05,5.6e-05,0.0041,0.022,0.029,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.1e-07,0.0036,0.0035,8.3e-05,0.00025,3.7e-05,0.00036,0.00017,0.00024,0.00036,1,1,0.01 +33590000,0.27,0.00087,-0.0037,0.96,-1.2,-0.75,0.86,0,0,-4.9e+02,-0.0014,-0.0057,-0.00018,0.011,0.0068,-0.11,0.21,-0.00068,0.43,-0.0039,-0.0014,0.002,0,0,-4.9e+02,6.4e-05,5.5e-05,0.0031,0.02,0.027,0.0052,0.34,0.37,0.03,2.4e-07,2.6e-07,7.9e-07,0.0036,0.0035,8.3e-05,0.00016,3.6e-05,0.00036,0.00012,0.00015,0.00036,1,1,0.01 +33690000,0.098,-0.0027,-0.0067,1,-1.1,-0.74,0.87,0,0,-4.9e+02,-0.0014,-0.0057,-0.00019,0.011,0.0068,-0.11,0.21,-0.00074,0.43,-0.0036,-0.001,0.002,0,0,-4.9e+02,6.4e-05,5.5e-05,0.0024,0.021,0.028,0.0053,0.35,0.37,0.031,2.4e-07,2.6e-07,7.8e-07,0.0036,0.0035,8.3e-05,0.0001,3.5e-05,0.00036,8.3e-05,9.8e-05,0.00036,1,1,0.01 +33790000,-0.074,-0.0046,-0.0085,1,-1.1,-0.72,0.85,0,0,-4.9e+02,-0.0014,-0.0057,-0.00021,0.011,0.0068,-0.11,0.21,-0.0009,0.43,-0.0021,-0.001,0.0023,0,0,-4.9e+02,6.2e-05,5.4e-05,0.0019,0.02,0.026,0.0052,0.35,0.37,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,6.8e-05,3.5e-05,0.00036,5.5e-05,6.1e-05,0.00036,1,1,0.01 +33890000,-0.24,-0.006,-0.0091,0.97,-0.99,-0.69,0.83,0,0,-4.9e+02,-0.0014,-0.0057,-0.00022,0.011,0.0068,-0.11,0.21,-0.001,0.43,-0.0013,-0.0011,0.0024,0,0,-4.9e+02,6.2e-05,5.4e-05,0.0016,0.022,0.028,0.0052,0.36,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,4.8e-05,3.4e-05,0.00036,3.8e-05,4.1e-05,0.00036,1,1,0.01 +33990000,-0.39,-0.0048,-0.012,0.92,-0.94,-0.64,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00022,0.011,0.0069,-0.11,0.21,-0.001,0.43,-0.0011,-0.00064,0.0025,0,0,-4.9e+02,6e-05,5.3e-05,0.0015,0.021,0.027,0.0052,0.36,0.37,0.03,2.4e-07,2.5e-07,7.7e-07,0.0036,0.0035,8.3e-05,3.6e-05,3.4e-05,0.00036,2.8e-05,2.9e-05,0.00036,1,1,0.01 +34090000,-0.5,-0.0039,-0.014,0.87,-0.88,-0.59,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00022,0.011,0.0072,-0.11,0.21,-0.00097,0.43,-0.0013,-0.00052,0.0025,0,0,-4.9e+02,6e-05,5.3e-05,0.0014,0.023,0.03,0.0052,0.37,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,3e-05,3.4e-05,0.00036,2.2e-05,2.3e-05,0.00036,1,1,0.01 +34190000,-0.57,-0.0038,-0.012,0.82,-0.85,-0.54,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00021,0.0086,0.0099,-0.11,0.21,-0.00096,0.43,-0.001,-0.00031,0.0028,0,0,-4.9e+02,5.7e-05,5.1e-05,0.0013,0.023,0.029,0.0052,0.37,0.38,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.5e-05,3.4e-05,0.00036,1.8e-05,1.8e-05,0.00036,1,1,0.01 +34290000,-0.61,-0.0048,-0.0091,0.79,-0.8,-0.48,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00021,0.0084,0.01,-0.11,0.21,-0.00098,0.43,-0.00093,-0.00018,0.0027,0,0,-4.9e+02,5.7e-05,5.1e-05,0.0012,0.025,0.032,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.2e-05,3.4e-05,0.00036,1.5e-05,1.5e-05,0.00036,1,1,0.01 +34390000,-0.63,-0.0054,-0.0062,0.77,-0.77,-0.44,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00019,0.0056,0.014,-0.11,0.21,-0.00094,0.43,-0.00092,1.8e-05,0.0029,0,0,-4.9e+02,5.4e-05,4.9e-05,0.0012,0.025,0.031,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,2e-05,3.3e-05,0.00036,1.3e-05,1.3e-05,0.00036,1,1,0.01 +34490000,-0.65,-0.0063,-0.004,0.76,-0.72,-0.39,0.81,0,0,-4.9e+02,-0.0015,-0.0057,-0.00019,0.0054,0.015,-0.11,0.21,-0.00095,0.43,-0.00086,-2.3e-05,0.0029,0,0,-4.9e+02,5.4e-05,4.9e-05,0.0011,0.027,0.035,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.1e-05,1.8e-05,3.3e-05,0.00036,1.2e-05,1.2e-05,0.00036,1,1,0.01 +34590000,-0.66,-0.0063,-0.0026,0.75,-0.7,-0.36,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,0.00036,0.021,-0.11,0.21,-0.00091,0.43,-0.00093,3.3e-05,0.0032,0,0,-4.9e+02,5e-05,4.7e-05,0.0011,0.027,0.034,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,1.1e-05,1e-05,0.00036,1,1,0.01 +34690000,-0.67,-0.0067,-0.0018,0.75,-0.64,-0.32,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,0.00011,0.021,-0.11,0.21,-0.00093,0.43,-0.00079,0.00023,0.0031,0,0,-4.9e+02,5e-05,4.7e-05,0.0011,0.03,0.037,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,9.9e-06,9.4e-06,0.00036,1,1,0.01 +34790000,-0.67,-0.0061,-0.0013,0.74,-0.63,-0.3,0.79,0,0,-4.9e+02,-0.0015,-0.0058,-0.00011,-0.0059,0.028,-0.11,0.21,-0.00092,0.43,-0.00063,0.00033,0.0033,0,0,-4.9e+02,4.6e-05,4.4e-05,0.001,0.029,0.036,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,9.1e-06,8.6e-06,0.00036,1,1,0.01 +34890000,-0.67,-0.0061,-0.0012,0.74,-0.57,-0.25,0.79,0,0,-4.9e+02,-0.0015,-0.0058,-0.00011,-0.0061,0.028,-0.11,0.21,-0.00092,0.43,-0.00064,0.00028,0.0033,0,0,-4.9e+02,4.6e-05,4.4e-05,0.001,0.032,0.04,0.0052,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,8.4e-06,7.9e-06,0.00036,1,1,0.01 +34990000,-0.67,-0.013,-0.0037,0.74,0.47,0.36,-0.043,0,0,-4.9e+02,-0.0016,-0.0058,-6.8e-05,-0.014,0.038,-0.11,0.21,-0.00089,0.43,-0.00052,0.00034,0.0035,0,0,-4.9e+02,4.2e-05,4.1e-05,0.001,0.034,0.046,0.0054,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.3e-05,3.3e-05,0.00036,8e-06,7.4e-06,0.00036,1,1,0.01 +35090000,-0.67,-0.013,-0.0037,0.74,0.61,0.39,-0.1,0,0,-4.9e+02,-0.0016,-0.0058,-6.9e-05,-0.014,0.038,-0.11,0.21,-0.00089,0.43,-0.00048,0.00029,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00099,0.037,0.051,0.0055,0.42,0.43,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.2e-05,3.3e-05,0.00036,7.5e-06,6.9e-06,0.00036,1,1,0.01 +35190000,-0.67,-0.013,-0.0038,0.74,0.64,0.43,-0.1,0,0,-4.9e+02,-0.0016,-0.0058,-7e-05,-0.014,0.038,-0.11,0.21,-0.0009,0.43,-0.00041,0.00033,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00099,0.041,0.055,0.0055,0.43,0.44,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.2e-05,3.3e-05,0.00036,7.1e-06,6.4e-06,0.00036,1,1,0.01 +35290000,-0.67,-0.013,-0.0039,0.74,0.67,0.48,-0.098,0,0,-4.9e+02,-0.0016,-0.0058,-7.1e-05,-0.014,0.038,-0.11,0.21,-0.00092,0.43,-0.00034,0.00033,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00098,0.044,0.06,0.0055,0.44,0.45,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.8e-06,6.1e-06,0.00036,1,1,0.01 +35390000,-0.67,-0.013,-0.0038,0.74,0.7,0.52,-0.096,0,0,-4.9e+02,-0.0016,-0.0058,-7.4e-05,-0.014,0.038,-0.11,0.21,-0.00093,0.43,-0.00024,0.0003,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00098,0.048,0.064,0.0055,0.46,0.47,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.5e-06,5.8e-06,0.00036,1,1,0.01 +35490000,-0.67,-0.013,-0.0039,0.74,0.73,0.56,-0.094,0,0,-4.9e+02,-0.0016,-0.0058,-7.7e-05,-0.014,0.038,-0.11,0.21,-0.00094,0.43,-0.00015,0.00025,0.0037,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00097,0.053,0.069,0.0055,0.47,0.48,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6.2e-06,5.5e-06,0.00036,1,1,0.01 +35590000,-0.67,-0.013,-0.0039,0.74,0.76,0.6,-0.093,0,0,-4.9e+02,-0.0016,-0.0058,-7.6e-05,-0.014,0.038,-0.11,0.21,-0.00094,0.43,-0.00017,0.00025,0.0036,0,0,-4.9e+02,4.2e-05,4.1e-05,0.00097,0.057,0.075,0.0055,0.49,0.5,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0032,8e-05,1.1e-05,3.3e-05,0.00036,6e-06,5.2e-06,0.00036,1,1,0.01 +35690000,-0.68,-0.013,-0.0038,0.74,0.79,0.65,-0.091,0,0,-4.9e+02,-0.0016,-0.0058,-7.7e-05,-0.014,0.038,-0.11,0.21,-0.00095,0.43,-9.9e-05,0.00024,0.0037,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.062,0.08,0.0056,0.51,0.52,0.031,2.4e-07,2.6e-07,7.4e-07,0.003,0.0032,8e-05,1e-05,3.3e-05,0.00036,5.8e-06,5e-06,0.00036,1,1,0.01 +35790000,-0.68,-0.013,-0.0038,0.74,0.82,0.69,-0.088,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.014,0.038,-0.11,0.21,-0.00095,0.43,-7.4e-05,0.00024,0.0037,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.067,0.086,0.0056,0.53,0.54,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.6e-06,4.8e-06,0.00036,1,1,0.023 +35890000,-0.68,-0.013,-0.0039,0.74,0.86,0.73,-0.085,0,0,-4.9e+02,-0.0016,-0.0058,-7.9e-05,-0.014,0.038,-0.11,0.21,-0.00096,0.43,-5.9e-05,0.00023,0.0037,0,0,-4.9e+02,4.2e-05,4.2e-05,0.00097,0.072,0.092,0.0056,0.55,0.56,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.4e-06,4.6e-06,0.00036,1,1,0.048 +35990000,-0.68,-0.013,-0.0039,0.74,0.89,0.77,-0.082,0,0,-4.9e+02,-0.0016,-0.0058,-7.8e-05,-0.014,0.038,-0.11,0.21,-0.00095,0.43,-8.4e-05,0.00022,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00097,0.078,0.099,0.0056,0.57,0.59,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.9e-06,3.3e-05,0.00036,5.3e-06,4.5e-06,0.00036,1,1,0.073 +36090000,-0.68,-0.013,-0.0039,0.74,0.92,0.81,-0.078,0,0,-4.9e+02,-0.0016,-0.0058,-8e-05,-0.014,0.038,-0.11,0.21,-0.00096,0.43,-4.9e-05,0.0002,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.083,0.11,0.0056,0.6,0.62,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.7e-06,3.3e-05,0.00036,5.2e-06,4.3e-06,0.00036,1,1,0.099 +36190000,-0.68,-0.013,-0.0039,0.74,0.95,0.86,-0.074,0,0,-4.9e+02,-0.0016,-0.0058,-8.4e-05,-0.014,0.038,-0.11,0.21,-0.00097,0.43,4.9e-05,0.00019,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.089,0.11,0.0056,0.63,0.65,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.5e-06,3.3e-05,0.00036,5e-06,4.2e-06,0.00036,1,1,0.12 +36290000,-0.68,-0.013,-0.0038,0.74,0.98,0.9,-0.069,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.014,0.037,-0.11,0.21,-0.00098,0.43,6.9e-05,0.00019,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.096,0.12,0.0056,0.66,0.68,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.4e-06,3.3e-05,0.00036,4.9e-06,4.1e-06,0.00036,1,1,0.15 +36390000,-0.68,-0.013,-0.0038,0.74,1,0.94,-0.066,0,0,-4.9e+02,-0.0016,-0.0058,-8.5e-05,-0.014,0.037,-0.11,0.21,-0.00098,0.43,6.6e-05,0.00022,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.1,0.13,0.0056,0.69,0.72,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.3e-06,3.3e-05,0.00036,4.8e-06,3.9e-06,0.00036,1,1,0.17 +36490000,-0.68,-0.013,-0.0039,0.74,1,0.98,-0.063,0,0,-4.9e+02,-0.0016,-0.0058,-8.3e-05,-0.014,0.037,-0.11,0.21,-0.00097,0.43,3.7e-05,0.00023,0.0037,0,0,-4.9e+02,4.3e-05,4.2e-05,0.00096,0.11,0.13,0.0056,0.72,0.76,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.2e-06,3.3e-05,0.00036,4.7e-06,3.8e-06,0.00036,1,1,0.2 +36590000,-0.68,-0.013,-0.0038,0.74,1.1,1,-0.057,0,0,-4.9e+02,-0.0016,-0.0058,-8.6e-05,-0.013,0.037,-0.11,0.21,-0.00098,0.43,8.5e-05,0.00026,0.0037,0,0,-4.9e+02,4.3e-05,4.3e-05,0.00096,0.12,0.14,0.0056,0.76,0.8,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.1e-06,3.3e-05,0.00036,4.6e-06,3.7e-06,0.00036,1,1,0.23 +36690000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.052,0,0,-4.9e+02,-0.0016,-0.0058,-8.8e-05,-0.013,0.037,-0.11,0.21,-0.00099,0.43,0.00012,0.00027,0.0037,0,0,-4.9e+02,4.3e-05,4.3e-05,0.00096,0.12,0.15,0.0057,0.8,0.85,0.032,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9e-06,3.3e-05,0.00036,4.6e-06,3.6e-06,0.00036,1,1,0.25 +36790000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.046,0,0,-4.9e+02,-0.0016,-0.0058,-9.2e-05,-0.013,0.037,-0.11,0.21,-0.001,0.43,0.00016,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.13,0.16,0.0057,0.84,0.9,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.9e-06,3.3e-05,0.00036,4.5e-06,3.5e-06,0.00036,1,1,0.28 +36890000,-0.68,-0.013,-0.0038,0.74,1.2,1.2,-0.041,0,0,-4.9e+02,-0.0016,-0.0058,-9.5e-05,-0.013,0.037,-0.11,0.21,-0.001,0.43,0.0002,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.14,0.17,0.0057,0.89,0.95,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.8e-06,3.3e-05,0.00036,4.4e-06,3.4e-06,0.00036,1,1,0.3 +36990000,-0.68,-0.013,-0.0037,0.74,1.2,1.2,-0.037,0,0,-4.9e+02,-0.0016,-0.0058,-9.6e-05,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00022,0.00023,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,0.94,1,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.7e-06,3.3e-05,0.00036,4.3e-06,3.4e-06,0.00036,1,1,0.33 +37090000,-0.68,-0.013,-0.0036,0.74,1.2,1.2,-0.031,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00023,0.00026,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.6e-06,3.3e-05,0.00036,4.3e-06,3.3e-06,0.00036,1,1,0.35 +37190000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.025,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00022,0.00027,0.0037,0,0,-4.9e+02,4.4e-05,4.3e-05,0.00096,0.16,0.19,0.0057,1.1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.6e-05,8.6e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00036,1,1,0.38 +37290000,-0.68,-0.013,-0.0037,0.74,1.3,1.3,-0.019,0,0,-4.9e+02,-0.0016,-0.0058,-9.8e-05,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00024,0.00027,0.0037,0,0,-4.9e+02,4.4e-05,4.4e-05,0.00096,0.17,0.2,0.0057,1.1,1.2,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00036,1,1,0.41 +37390000,-0.68,-0.013,-0.0036,0.74,1.3,1.4,-0.015,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00026,0.00027,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.18,0.21,0.0057,1.2,1.3,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3.1e-06,0.00036,1,1,0.43 +37490000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0088,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.0003,0.0003,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.19,0.22,0.0057,1.3,1.4,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3e-06,0.00036,1,1,0.46 +37590000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,-0.0022,0,0,-4.9e+02,-0.0016,-0.0058,-0.0001,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00031,0.00031,0.0037,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.2,0.23,0.0057,1.3,1.5,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.3e-06,3.3e-05,0.00036,4e-06,3e-06,0.00036,1,1,0.48 +37690000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,0.0051,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.013,0.036,-0.11,0.21,-0.001,0.43,0.00033,0.00029,0.0038,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.21,0.24,0.0057,1.4,1.6,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00036,1,1,0.51 +37790000,-0.68,-0.013,-0.0036,0.74,1.5,1.5,0.012,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.013,0.035,-0.11,0.21,-0.001,0.43,0.00034,0.0003,0.0038,0,0,-4.9e+02,4.5e-05,4.4e-05,0.00096,0.22,0.26,0.0057,1.5,1.7,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00036,1,1,0.54 +37890000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.018,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.013,0.035,-0.11,0.21,-0.001,0.43,0.00034,0.00029,0.0038,0,0,-4.9e+02,4.5e-05,4.5e-05,0.00096,0.23,0.27,0.0056,1.6,1.8,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00036,1,1,0.56 +37990000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.026,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.013,0.035,-0.11,0.21,-0.001,0.43,0.00035,0.00029,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.24,0.28,0.0057,1.7,1.9,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00036,1,1,0.59 +38090000,-0.68,-0.014,-0.0036,0.74,1.6,1.7,0.034,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00036,0.0003,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.25,0.29,0.0056,1.8,2,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00036,1,1,0.61 +38190000,-0.68,-0.013,-0.0036,0.74,1.6,1.7,0.04,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00037,0.00029,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.26,0.3,0.0056,1.9,2.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00036,1,1,0.64 +38290000,-0.68,-0.014,-0.0036,0.74,1.6,1.8,0.047,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00037,0.00028,0.0038,0,0,-4.9e+02,4.6e-05,4.5e-05,0.00096,0.27,0.31,0.0056,2.1,2.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00036,1,1,0.67 +38390000,-0.68,-0.014,-0.0035,0.74,1.7,1.8,0.052,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00037,0.0003,0.0038,0,0,-4.9e+02,4.6e-05,4.6e-05,0.00096,0.28,0.33,0.0056,2.2,2.5,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00036,1,1,0.69 +38490000,-0.68,-0.014,-0.0035,0.74,1.7,1.8,0.058,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00038,0.00032,0.0038,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.29,0.34,0.0056,2.3,2.6,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00036,1,1,0.72 +38590000,-0.68,-0.014,-0.0034,0.74,1.7,1.9,0.064,0,0,-4.9e+02,-0.0016,-0.0058,-0.00011,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00037,0.00032,0.0038,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.3,0.35,0.0056,2.5,2.8,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.6e-06,0.00036,1,1,0.75 +38690000,-0.68,-0.014,-0.0034,0.74,1.7,1.9,0.069,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.00039,0.00034,0.0038,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.31,0.36,0.0056,2.6,3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00036,1,1,0.77 +38790000,-0.68,-0.014,-0.0034,0.74,1.8,2,0.075,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.0004,0.00033,0.0038,0,0,-4.9e+02,4.7e-05,4.6e-05,0.00097,0.33,0.38,0.0056,2.8,3.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.8 +38890000,-0.68,-0.014,-0.0035,0.74,1.8,2,0.57,0,0,-4.9e+02,-0.0016,-0.0058,-0.00012,-0.012,0.035,-0.11,0.21,-0.001,0.43,0.0004,0.00031,0.0038,0,0,-4.9e+02,4.8e-05,4.7e-05,0.00097,0.33,0.39,0.0056,3,3.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.7e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.83 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index b9bbada6df04..f83bc0ad462c 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -15,337 +15,337 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.1,0,0,-4.9e+02,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00079,0,0,0,0,0,0,0,0,-4.9e+02,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.094,0,0,-4.9e+02,-0.00016,-9.3e-05,1.5e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,-4.9e+02,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.11,0,0,-4.9e+02,-0.00039,-0.00033,1.2e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,-4.9e+02,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -1590000,1,-0.012,-0.014,0.0004,0.031,-0.024,-0.13,0,0,-4.9e+02,-0.00039,-0.00033,1.2e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,-4.9e+02,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.012,-0.014,0.00045,0.028,-0.019,-0.13,0,0,-4.9e+02,-0.00073,-0.00074,-3.4e-07,0,0,-0.0018,0,0,0,0,0,0,0,0,-4.9e+02,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0,0,-4.9e+02,-0.00073,-0.00073,-2.9e-07,0,0,-0.0028,0,0,0,0,0,0,0,0,-4.9e+02,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0,0,-4.9e+02,-0.00039,-0.00033,1.2e-06,0,0,-0.0014,0,0,0,0,0,0,0,0,-4.9e+02,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0,0,-4.9e+02,-0.00073,-0.00074,-3.5e-07,0,0,-0.0018,0,0,0,0,0,0,0,0,-4.9e+02,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0,0,-4.9e+02,-0.00073,-0.00073,-3e-07,0,0,-0.0028,0,0,0,0,0,0,0,0,-4.9e+02,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0,0,-4.9e+02,-0.00072,-0.00072,-2.7e-07,0,0,-0.0032,0,0,0,0,0,0,0,0,-4.9e+02,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,0.00041,0.035,-0.018,-0.14,0,0,-4.9e+02,-0.0011,-0.0013,-3.6e-06,0,0,-0.0046,0,0,0,0,0,0,0,0,-4.9e+02,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0,0,-4.9e+02,-0.0011,-0.0013,-3.7e-06,0,0,-0.0046,0,0,0,0,0,0,0,0,-4.9e+02,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0,0,-4.9e+02,-0.0011,-0.0012,-3.5e-06,0,0,-0.0064,0,0,0,0,0,0,0,0,-4.9e+02,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,0.00039,0.033,-0.014,-0.14,0,0,-4.9e+02,-0.0014,-0.0018,-8.7e-06,0,0,-0.0075,0,0,0,0,0,0,0,0,-4.9e+02,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,0.00039,0.038,-0.014,-0.14,0,0,-4.9e+02,-0.0014,-0.0018,-8.5e-06,0,0,-0.0097,0,0,0,0,0,0,0,0,-4.9e+02,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,0.0004,0.029,-0.01,-0.14,0,0,-4.9e+02,-0.0017,-0.0023,-1.4e-05,0,0,-0.012,0,0,0,0,0,0,0,0,-4.9e+02,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.014,0.00048,0.033,-0.0091,-0.14,0,0,-4.9e+02,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0,0,0,0,0,0,0,0,-4.9e+02,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.01,-0.013,0.0004,0.023,-0.0062,-0.15,0,0,-4.9e+02,-0.0018,-0.0027,-2e-05,0,0,-0.015,0,0,0,0,0,0,0,0,-4.9e+02,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.01,-0.013,0.00044,0.027,-0.0055,-0.15,0,0,-4.9e+02,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,-4.9e+02,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.01,-0.013,0.00038,0.022,-0.0032,-0.14,0,0,-4.9e+02,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.01,-0.013,0.00031,0.026,-0.005,-0.14,0,0,-4.9e+02,-0.0019,-0.003,-2.5e-05,0,0,-0.025,0,0,0,0,0,0,0,0,-4.9e+02,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.01,-0.013,0.00033,0.02,-0.0039,-0.15,0,0,-4.9e+02,-0.002,-0.0033,-3e-05,0,0,-0.028,0,0,0,0,0,0,0,0,-4.9e+02,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.01,-0.013,0.00053,0.025,-0.0068,-0.15,0,0,-4.9e+02,-0.002,-0.0033,-3e-05,0,0,-0.031,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.01,-0.013,0.00058,0.02,-0.0065,-0.15,0,0,-4.9e+02,-0.0021,-0.0036,-3.5e-05,0,0,-0.032,0,0,0,0,0,0,0,0,-4.9e+02,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.01,-0.013,0.0006,0.023,-0.0067,-0.15,0,0,-4.9e+02,-0.0021,-0.0036,-3.4e-05,0,0,-0.034,0,0,0,0,0,0,0,0,-4.9e+02,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.0098,-0.013,0.00061,0.019,-0.0036,-0.15,0,0,-4.9e+02,-0.0021,-0.0038,-3.8e-05,0,0,-0.039,0,0,0,0,0,0,0,0,-4.9e+02,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.0097,-0.013,0.0006,0.025,-0.0023,-0.15,0,0,-4.9e+02,-0.0021,-0.0038,-3.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,-4.9e+02,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.0095,-0.012,0.00056,0.021,-0.0018,-0.15,0,0,-4.9e+02,-0.0022,-0.004,-4.2e-05,0,0,-0.046,0,0,0,0,0,0,0,0,-4.9e+02,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.0095,-0.013,0.00054,0.024,-0.0011,-0.15,0,0,-4.9e+02,-0.0022,-0.004,-4.2e-05,0,0,-0.051,0,0,0,0,0,0,0,0,-4.9e+02,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.0094,-0.012,0.00057,0.019,0.0033,-0.15,0,0,-4.9e+02,-0.0022,-0.0043,-4.7e-05,0,0,-0.054,0,0,0,0,0,0,0,0,-4.9e+02,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.0094,-0.013,0.00065,0.021,0.0045,-0.14,0,0,-4.9e+02,-0.0022,-0.0042,-4.7e-05,0,0,-0.058,0,0,0,0,0,0,0,0,-4.9e+02,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.0094,-0.013,0.00072,0.026,0.0042,-0.14,0,0,-4.9e+02,-0.0022,-0.0042,-4.7e-05,0,0,-0.063,0,0,0,0,0,0,0,0,-4.9e+02,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.0093,-0.012,0.00078,0.022,0.0037,-0.12,0,0,-4.9e+02,-0.0022,-0.0044,-5.1e-05,0,0,-0.071,0,0,0,0,0,0,0,0,-4.9e+02,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.0094,-0.012,0.00075,0.024,0.0034,-0.12,0,0,-4.9e+02,-0.0022,-0.0044,-5.1e-05,0,0,-0.074,0,0,0,0,0,0,0,0,-4.9e+02,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.0095,-0.012,0.00076,0.021,0.0033,-0.13,0,0,-4.9e+02,-0.0022,-0.0046,-5.6e-05,0,0,-0.076,0,0,0,0,0,0,0,0,-4.9e+02,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.0094,-0.012,0.00072,0.025,0.0018,-0.11,0,0,-4.9e+02,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,-4.9e+02,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.0094,-0.012,0.00078,0.021,0.0036,-0.11,0,0,-4.9e+02,-0.0022,-0.0048,-6.1e-05,0,0,-0.086,0,0,0,0,0,0,0,0,-4.9e+02,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.0094,-0.012,0.00085,0.023,0.0024,-0.11,0,0,-4.9e+02,-0.0022,-0.0048,-6.1e-05,0,0,-0.088,0,0,0,0,0,0,0,0,-4.9e+02,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.0094,-0.012,0.00079,0.017,0.0027,-0.1,0,0,-4.9e+02,-0.0021,-0.005,-6.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,-4.9e+02,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.0093,-0.012,0.00089,0.015,0.0048,-0.1,0,0,-4.9e+02,-0.0021,-0.005,-6.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,-4.9e+02,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.0093,-0.012,0.00093,0.01,0.0024,-0.093,0,0,-4.9e+02,-0.0021,-0.0051,-6.9e-05,0,0,-0.099,0,0,0,0,0,0,0,0,-4.9e+02,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.0092,-0.012,0.00091,0.013,0.0031,-0.085,0,0,-4.9e+02,-0.0021,-0.0051,-6.9e-05,0,0,-0.1,0,0,0,0,0,0,0,0,-4.9e+02,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.0091,-0.011,0.00099,0.01,0.0034,-0.083,0,0,-4.9e+02,-0.0021,-0.0052,-7.2e-05,0,0,-0.1,0,0,0,0,0,0,0,0,-4.9e+02,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.0089,-0.012,0.001,0.0099,0.007,-0.08,0,0,-4.9e+02,-0.0021,-0.0052,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0071,-0.069,0,0,-4.9e+02,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0,0,-4.9e+02,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.061,0,0,-4.9e+02,-0.002,-0.0054,-7.7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.054,0,0,-4.9e+02,-0.002,-0.0054,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0089,-0.011,0.00093,0.0077,0.016,-0.053,0,0,-4.9e+02,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0088,-0.011,0.00088,0.0089,0.018,-0.05,0,0,-4.9e+02,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0088,-0.011,0.00092,0.0095,0.015,-0.048,0,0,-4.9e+02,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0088,-0.012,0.00089,0.011,0.017,-0.042,0,0,-4.9e+02,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0088,-0.011,0.00071,0.011,0.018,-0.039,0,0,-4.9e+02,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0089,-0.011,0.00072,0.0087,0.017,-0.038,0,0,-4.9e+02,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0089,-0.011,0.00075,0.008,0.019,-0.041,0,0,-4.9e+02,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0089,-0.011,0.00076,0.0082,0.016,-0.042,0,0,-4.9e+02,-0.0018,-0.0056,-8.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0089,-0.011,0.00066,0.0057,0.016,-0.04,0,0,-4.9e+02,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.0089,-0.011,0.00059,0.0039,0.015,-0.042,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0088,-0.011,0.00055,0.0022,0.018,-0.044,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,1,-0.0089,-0.011,0.00052,0.0029,0.015,-0.043,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6890000,1,-0.0087,-0.011,0.00043,0.0023,0.015,-0.039,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,0.98,-0.0067,-0.012,0.18,0.0025,0.011,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,-4.9e+02,0.0012,0.0012,0.054,0.16,0.17,0.031,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 -7090000,0.98,-0.0065,-0.012,0.18,0.00012,0.018,-0.038,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,-4.9e+02,0.0013,0.0013,0.048,0.18,0.19,0.03,0.13,0.13,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 -7190000,0.98,-0.0065,-0.012,0.18,-6.1e-05,0.019,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.7e-06,0,0,-4.9e+02,0.0013,0.0013,0.046,0.21,0.21,0.029,0.16,0.16,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 -7290000,0.98,-0.0064,-0.012,0.18,-0.00068,0.024,-0.034,0,0,-4.9e+02,-0.0016,-0.0057,-9.2e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,-4.9e+02,0.0014,0.0013,0.044,0.24,0.24,0.028,0.19,0.19,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7390000,0.98,-0.0063,-0.012,0.18,-0.0015,0.00094,-0.032,0,0,-4.9e+02,-0.0017,-0.0057,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-5.7e-05,0.43,-0.00048,-0.0004,8.8e-05,0,0,-4.9e+02,0.0014,0.0014,0.043,25,25,0.027,1e+02,1e+02,0.064,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00027,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7490000,0.98,-0.0063,-0.012,0.18,0.00097,0.0035,-0.026,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-4.5e-05,0.43,-0.00042,-0.00038,-7.9e-05,0,0,-4.9e+02,0.0015,0.0014,0.043,25,25,0.026,1e+02,1e+02,0.063,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00022,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7590000,0.98,-0.0064,-0.012,0.18,0.0021,0.006,-0.023,0,0,-4.9e+02,-0.0017,-0.0056,-9e-05,-0.00036,0.00036,-0.13,0.2,-3.8e-05,0.43,-0.00034,-0.00039,-9.5e-06,0,0,-4.9e+02,0.0015,0.0015,0.042,25,25,0.025,51,51,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00019,0.0013,0.0014,0.0016,0.0013,1,1,1.9 -7690000,0.98,-0.0064,-0.013,0.18,0.0021,0.0093,-0.022,0,0,-4.9e+02,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-3.4e-05,0.43,-0.00031,-0.0004,2.4e-06,0,0,-4.9e+02,0.0016,0.0015,0.042,25,25,0.025,52,52,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00017,0.0013,0.0014,0.0016,0.0013,1,1,2 -7790000,0.98,-0.0064,-0.013,0.18,0.0056,0.01,-0.025,0,0,-4.9e+02,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.9e-05,0.43,-0.00021,-0.00039,-1.5e-06,0,0,-4.9e+02,0.0016,0.0016,0.042,24,24,0.024,35,35,0.061,6.3e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00015,0.0013,0.0014,0.0016,0.0013,1,1,2 -7890000,0.98,-0.0065,-0.013,0.18,0.0046,0.014,-0.025,0,0,-4.9e+02,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.6e-05,0.43,-0.00019,-0.0004,4.4e-05,0,0,-4.9e+02,0.0016,0.0016,0.042,24,24,0.023,36,36,0.06,6.3e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00013,0.0013,0.0014,0.0016,0.0013,1,1,2 -7990000,0.98,-0.0063,-0.013,0.18,0.0032,0.017,-0.022,0,0,-4.9e+02,-0.0016,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-2.5e-05,0.43,-0.0002,-0.00042,7.4e-05,0,0,-4.9e+02,0.0017,0.0016,0.042,24,24,0.022,28,28,0.059,6.2e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00012,0.0013,0.0014,0.0016,0.0013,1,1,2 -8090000,0.98,-0.0063,-0.013,0.18,0.0043,0.019,-0.022,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,-0.00036,0.00036,-0.13,0.2,-2.2e-05,0.43,-0.00017,-0.00042,9.9e-05,0,0,-4.9e+02,0.0017,0.0017,0.042,24,24,0.022,30,30,0.059,6.2e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,0.00011,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8190000,0.98,-0.0064,-0.012,0.18,0.0052,0.022,-0.018,0,0,-4.9e+02,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.44,-0.00014,-0.00041,0.00014,0,0,-4.9e+02,0.0018,0.0017,0.041,23,23,0.021,24,24,0.058,6.1e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,0.0001,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8290000,0.98,-0.0062,-0.012,0.18,0.002,0.028,-0.017,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.43,-0.00014,-0.00044,6.7e-05,0,0,-4.9e+02,0.0018,0.0017,0.041,23,23,0.02,27,27,0.057,6.1e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,9.6e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8390000,0.98,-0.0062,-0.012,0.18,-0.0023,0.028,-0.016,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00044,2.1e-05,0,0,-4.9e+02,0.0019,0.0018,0.041,21,21,0.02,23,23,0.057,6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 -8490000,0.98,-0.0059,-0.012,0.18,-0.0061,0.035,-0.017,0,0,-4.9e+02,-0.0017,-0.0059,-9.6e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00048,-7.4e-06,0,0,-4.9e+02,0.0019,0.0018,0.041,21,21,0.019,25,25,0.056,5.9e-05,5.6e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8590000,0.98,-0.006,-0.012,0.18,-0.00035,0.034,-0.012,0,0,-4.9e+02,-0.0016,-0.0057,-9.6e-05,-0.00036,0.00036,-0.14,0.2,-1.7e-05,0.43,-0.00018,-0.00043,3.3e-06,0,0,-4.9e+02,0.0019,0.0018,0.041,19,19,0.018,22,22,0.055,5.8e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,7.9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8690000,0.98,-0.006,-0.012,0.18,-0.0022,0.037,-0.014,0,0,-4.9e+02,-0.0016,-0.0058,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-1.6e-05,0.43,-0.00022,-0.00045,-8.7e-05,0,0,-4.9e+02,0.002,0.0018,0.041,19,19,0.018,24,24,0.055,5.8e-05,5.3e-05,2.2e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8790000,0.98,-0.006,-0.012,0.18,-0.005,0.039,-0.014,0,0,-4.9e+02,-0.0016,-0.0058,-9.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00019,-0.00045,-0.00013,0,0,-4.9e+02,0.002,0.0018,0.041,19,19,0.018,27,27,0.055,5.7e-05,5.2e-05,2.2e-06,0.04,0.04,0.00099,0.0013,7.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 -8890000,0.98,-0.006,-0.012,0.18,0.00053,0.041,-0.0094,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00026,-0.00043,-0.00011,0,0,-4.9e+02,0.002,0.0018,0.041,17,17,0.017,24,24,0.054,5.6e-05,5e-05,2.2e-06,0.04,0.04,0.00094,0.0013,6.7e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 -8990000,0.98,-0.0059,-0.013,0.18,0.01,0.047,-0.0086,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00037,-0.00039,-6.6e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,17,17,0.017,27,27,0.054,5.5e-05,4.9e-05,2.2e-06,0.04,0.04,0.00091,0.0013,6.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 -9090000,0.98,-0.0055,-0.012,0.18,-0.00033,0.056,-0.0096,0,0,-4.9e+02,-0.0018,-0.0057,-8.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00028,-0.00049,-8.8e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,15,15,0.016,24,24,0.053,5.3e-05,4.7e-05,2.2e-06,0.04,0.04,0.00087,0.0013,6.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 -9190000,0.98,-0.0053,-0.013,0.18,0.0029,0.064,-0.009,0,0,-4.9e+02,-0.0018,-0.0057,-8.6e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00031,-0.00053,-0.00011,0,0,-4.9e+02,0.0021,0.0018,0.041,15,15,0.016,27,27,0.052,5.2e-05,4.5e-05,2.2e-06,0.04,0.04,0.00083,0.0013,5.9e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.3 -9290000,0.98,-0.0053,-0.013,0.18,0.013,0.062,-0.0074,0,0,-4.9e+02,-0.0018,-0.0056,-8.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.0004,-0.00049,-8.5e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,13,13,0.015,24,24,0.052,5.1e-05,4.4e-05,2.2e-06,0.04,0.04,0.00079,0.0013,5.6e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 -9390000,0.98,-0.0054,-0.013,0.18,0.014,0.06,-0.0063,0,0,-4.9e+02,-0.0017,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00035,-0.00043,-3.8e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,13,13,0.015,26,26,0.052,5e-05,4.2e-05,2.2e-06,0.04,0.04,0.00077,0.0013,5.4e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 -9490000,0.98,-0.0053,-0.013,0.18,0.0087,0.061,-0.0046,0,0,-4.9e+02,-0.0018,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00033,-0.00048,-7.6e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,12,12,0.015,23,23,0.051,4.8e-05,4e-05,2.2e-06,0.04,0.04,0.00074,0.0013,5.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 -9590000,0.98,-0.0057,-0.013,0.18,0.0078,0.052,-0.0045,0,0,-4.9e+02,-0.0016,-0.0057,-9.3e-05,-0.00036,0.00036,-0.14,0.2,-1e-05,0.43,-0.00031,-0.00041,-0.00012,0,0,-4.9e+02,0.0022,0.0018,0.041,12,12,0.014,26,26,0.05,4.7e-05,3.9e-05,2.2e-06,0.04,0.04,0.00071,0.0013,5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 -9690000,0.98,-0.0059,-0.013,0.18,0.0096,0.047,-0.0016,0,0,-4.9e+02,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-9.2e-06,0.43,-0.00031,-0.00038,-9.9e-05,0,0,-4.9e+02,0.0022,0.0018,0.041,10,10,0.014,23,23,0.05,4.6e-05,3.7e-05,2.2e-06,0.04,0.04,0.00068,0.0013,4.8e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -9790000,0.98,-0.0061,-0.012,0.18,0.001,0.041,-0.003,0,0,-4.9e+02,-0.0015,-0.0058,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.7e-06,0.43,-0.00019,-0.00036,-0.00015,0,0,-4.9e+02,0.0022,0.0017,0.041,10,10,0.014,25,25,0.05,4.4e-05,3.5e-05,2.2e-06,0.04,0.04,0.00066,0.0013,4.7e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -9890000,0.98,-0.0061,-0.012,0.18,0.0086,0.04,-0.0017,0,0,-4.9e+02,-0.0015,-0.0057,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.6e-06,0.43,-0.00023,-0.00034,-9.4e-05,0,0,-4.9e+02,0.0022,0.0017,0.041,8.6,8.7,0.013,22,22,0.049,4.3e-05,3.4e-05,2.2e-06,0.04,0.04,0.00063,0.0013,4.5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -9990000,0.98,-0.0063,-0.012,0.18,0.0025,0.034,-0.001,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-6.4e-06,0.43,-0.00014,-0.00033,-0.00013,0,0,-4.9e+02,0.0022,0.0017,0.041,8.6,8.7,0.013,24,24,0.049,4.2e-05,3.2e-05,2.2e-06,0.04,0.04,0.00061,0.0013,4.4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 -10090000,0.98,-0.0067,-0.012,0.18,0.00072,0.019,0.00016,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-4.9e-06,0.43,-9.8e-05,-0.00025,-0.00015,0,0,-4.9e+02,0.0022,0.0017,0.041,7.4,7.5,0.013,21,21,0.048,4e-05,3.1e-05,2.2e-06,0.04,0.04,0.00059,0.0013,4.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10190000,0.98,-0.0072,-0.012,0.18,0.0053,0.0047,0.001,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00036,0.00036,-0.14,0.2,-3.3e-06,0.43,-9.1e-05,-0.00012,-0.00015,0,0,-4.9e+02,0.0022,0.0016,0.041,7.4,7.6,0.012,23,23,0.048,3.9e-05,2.9e-05,2.2e-06,0.04,0.04,0.00057,0.0013,4.1e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10290000,0.98,-0.0071,-0.012,0.18,0.012,0.0085,-3.9e-05,0,0,-4.9e+02,-0.0012,-0.0057,-0.00011,-0.00036,0.00036,-0.14,0.2,-3.7e-06,0.43,-0.00016,-0.00011,-0.00012,0,0,-4.9e+02,0.0022,0.0016,0.041,6.4,6.5,0.012,20,20,0.048,3.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10390000,0.98,-0.0071,-0.012,0.18,0.0076,0.0026,-0.0025,0,0,-4.9e+02,-0.0012,-0.0056,-0.00011,-0.0003,0.00041,-0.14,0.2,-3.9e-06,0.43,-0.0002,-0.00011,-6.5e-05,0,0,-4.9e+02,0.0022,0.0016,0.041,0.25,0.25,0.56,0.5,0.5,0.048,3.6e-05,2.7e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10490000,0.98,-0.0073,-0.012,0.18,0.0096,0.00082,0.007,0,0,-4.9e+02,-0.0011,-0.0057,-0.00011,-0.00033,0.00027,-0.14,0.2,-3e-06,0.43,-0.00016,-5.9e-05,-8.7e-05,0,0,-4.9e+02,0.0021,0.0016,0.041,0.25,0.26,0.55,0.51,0.51,0.057,3.5e-05,2.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10590000,0.98,-0.007,-0.012,0.18,0.00031,-0.00018,0.013,0,0,-4.9e+02,-0.0012,-0.0056,-0.00011,-0.0003,0.00025,-0.14,0.2,-3.6e-06,0.43,-0.00018,-9.8e-05,-7.3e-05,0,0,-4.9e+02,0.0021,0.0015,0.041,0.13,0.13,0.27,0.17,0.17,0.055,3.3e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10690000,0.98,-0.0071,-0.013,0.18,0.0031,-0.0028,0.016,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.00027,0.00018,-0.14,0.2,-3.3e-06,0.43,-0.00021,-4.9e-05,-7e-05,0,0,-4.9e+02,0.0021,0.0015,0.041,0.13,0.14,0.26,0.17,0.18,0.065,3.2e-05,2.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10790000,0.98,-0.0073,-0.013,0.18,0.0057,-0.006,0.014,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.00016,7.3e-05,-0.14,0.2,-3.1e-06,0.43,-0.00026,1.3e-05,-9e-05,0,0,-4.9e+02,0.002,0.0014,0.041,0.09,0.095,0.17,0.11,0.11,0.061,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10890000,0.98,-0.0069,-0.013,0.18,0.008,-0.0029,0.01,0,0,-4.9e+02,-0.0012,-0.0055,-0.00011,-5.4e-05,0.0002,-0.14,0.2,-4.1e-06,0.43,-0.00033,-3e-05,-7.2e-05,0,0,-4.9e+02,0.002,0.0014,0.041,0.097,0.1,0.16,0.11,0.11,0.068,2.9e-05,2e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -10990000,0.98,-0.0069,-0.013,0.18,0.0054,0.0032,0.016,0,0,-4.9e+02,-0.0012,-0.0056,-0.00011,-0.00021,0.00015,-0.14,0.2,-4.1e-06,0.43,-0.00026,-5.9e-05,-0.00012,0,0,-4.9e+02,0.0019,0.0014,0.041,0.074,0.081,0.12,0.079,0.079,0.065,2.6e-05,1.9e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11090000,0.98,-0.0075,-0.013,0.18,0.0093,0.0017,0.02,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.0003,-5.8e-05,-0.14,0.2,-2.9e-06,0.43,-0.00024,2.5e-05,-0.0001,0,0,-4.9e+02,0.0019,0.0013,0.041,0.082,0.093,0.11,0.084,0.085,0.069,2.6e-05,1.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11190000,0.98,-0.0077,-0.013,0.18,0.0083,0.0023,0.026,0,0,-4.9e+02,-0.001,-0.0056,-0.00012,-0.00041,-1.3e-05,-0.14,0.2,-2.4e-06,0.43,-0.00017,-1.2e-06,-0.00012,0,0,-4.9e+02,0.0017,0.0013,0.04,0.066,0.076,0.084,0.065,0.066,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11290000,0.98,-0.0077,-0.012,0.18,0.0065,-0.0003,0.025,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00052,0.00011,-0.14,0.2,-2.2e-06,0.43,-0.0001,-4e-05,-0.00015,0,0,-4.9e+02,0.0017,0.0012,0.04,0.074,0.088,0.078,0.071,0.072,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11390000,0.98,-0.0076,-0.012,0.18,0.0045,0.00081,0.016,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00054,1.8e-05,-0.14,0.2,-2.3e-06,0.43,-7.8e-05,-5.1e-05,-0.00018,0,0,-4.9e+02,0.0015,0.0012,0.04,0.062,0.074,0.064,0.058,0.058,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11490000,0.98,-0.0075,-0.012,0.18,0.0052,-0.00071,0.02,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00052,-6.5e-05,-0.14,0.2,-2.3e-06,0.43,-9.9e-05,-3e-05,-0.00017,0,0,-4.9e+02,0.0015,0.0011,0.04,0.071,0.086,0.058,0.063,0.064,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11590000,0.98,-0.0076,-0.012,0.18,0.0047,-0.00064,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00061,2.5e-05,-0.14,0.2,-2.3e-06,0.43,-5e-05,-6.9e-05,-0.00019,0,0,-4.9e+02,0.0014,0.0011,0.04,0.06,0.072,0.049,0.053,0.054,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11690000,0.98,-0.0075,-0.012,0.18,0.0042,0.0018,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00057,0.00015,-0.14,0.2,-2.5e-06,0.43,-4.4e-05,-8.6e-05,-0.00022,0,0,-4.9e+02,0.0014,0.001,0.04,0.068,0.084,0.046,0.059,0.06,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11790000,0.98,-0.0075,-0.012,0.18,0.0028,0.0026,0.019,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-4.6e-05,0.00011,-0.14,0.2,-2.6e-06,0.43,-5.7e-05,-9.1e-05,-0.00022,0,0,-4.9e+02,0.0012,0.00096,0.039,0.058,0.07,0.039,0.05,0.051,0.062,1.3e-05,9.4e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11890000,0.98,-0.0077,-0.012,0.18,0.0039,0.0012,0.017,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00025,0.00027,-0.14,0.2,-2.4e-06,0.43,-2.6e-05,-9.1e-05,-0.00026,0,0,-4.9e+02,0.0012,0.00096,0.039,0.066,0.082,0.036,0.056,0.058,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11990000,0.98,-0.0077,-0.012,0.18,0.0067,0.0034,0.014,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00032,0.00042,-0.14,0.2,-2.7e-06,0.43,-4.4e-05,-9.8e-05,-0.00026,0,0,-4.9e+02,0.0011,0.00088,0.039,0.057,0.068,0.032,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -12090000,0.98,-0.0077,-0.012,0.18,0.0099,0.001,0.017,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00051,0.00017,-0.14,0.2,-2.4e-06,0.43,-4.3e-05,-6.6e-05,-0.00025,0,0,-4.9e+02,0.0011,0.00088,0.039,0.064,0.079,0.029,0.055,0.056,0.06,1e-05,7.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12190000,0.98,-0.0077,-0.012,0.18,0.011,-0.00015,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0012,-0.00048,-0.14,0.2,-2.3e-06,0.43,-6.9e-06,-3e-05,-0.00028,0,0,-4.9e+02,0.00094,0.00081,0.039,0.055,0.065,0.026,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12290000,0.98,-0.0078,-0.012,0.18,0.0081,-0.0036,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0015,-0.00031,-0.14,0.2,-2.1e-06,0.43,2e-05,-3.8e-05,-0.00028,0,0,-4.9e+02,0.00095,0.00081,0.039,0.062,0.075,0.024,0.054,0.056,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12390000,0.98,-0.0079,-0.012,0.18,0.008,-0.0049,0.013,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0018,-0.00078,-0.14,0.2,-2e-06,0.43,4.7e-05,-1.7e-05,-0.0003,0,0,-4.9e+02,0.00085,0.00075,0.039,0.053,0.062,0.022,0.047,0.048,0.056,6.9e-06,5.6e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12490000,0.98,-0.008,-0.012,0.18,0.0096,-0.0064,0.017,0,0,-4.9e+02,-0.00099,-0.0058,-0.00013,-0.0021,-0.001,-0.14,0.2,-1.9e-06,0.43,5.5e-05,1.3e-05,-0.00031,0,0,-4.9e+02,0.00085,0.00075,0.039,0.06,0.071,0.021,0.053,0.055,0.056,6.8e-06,5.4e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12590000,0.98,-0.0081,-0.012,0.18,0.012,-0.01,0.018,0,0,-4.9e+02,-0.00098,-0.0058,-0.00013,-0.0022,-0.0009,-0.14,0.2,-1.8e-06,0.43,6.9e-05,1.3e-05,-0.00032,0,0,-4.9e+02,0.00077,0.0007,0.039,0.051,0.059,0.019,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12690000,0.98,-0.008,-0.012,0.18,0.012,-0.014,0.018,0,0,-4.9e+02,-0.00097,-0.0058,-0.00013,-0.0024,-0.00085,-0.14,0.2,-1.8e-06,0.43,7.9e-05,1.7e-05,-0.00033,0,0,-4.9e+02,0.00077,0.00069,0.039,0.057,0.067,0.018,0.053,0.055,0.054,5.7e-06,4.6e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12790000,0.98,-0.0081,-0.012,0.18,0.014,-0.012,0.02,0,0,-4.9e+02,-0.00098,-0.0058,-0.00013,-0.0017,-0.0013,-0.14,0.2,-1.8e-06,0.43,4.4e-05,4.1e-05,-0.00031,0,0,-4.9e+02,0.0007,0.00065,0.039,0.049,0.056,0.016,0.046,0.047,0.052,4.8e-06,4.1e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12890000,0.98,-0.008,-0.012,0.18,0.016,-0.013,0.021,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.0014,-0.0015,-0.14,0.2,-1.9e-06,0.43,2.4e-05,4.5e-05,-0.00029,0,0,-4.9e+02,0.00071,0.00065,0.039,0.055,0.063,0.016,0.052,0.054,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -12990000,0.98,-0.0079,-0.012,0.18,0.013,-0.0088,0.021,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0013,-0.0016,-0.14,0.2,-2.4e-06,0.43,3.8e-05,2e-05,-0.00032,0,0,-4.9e+02,0.00065,0.00061,0.038,0.047,0.053,0.014,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13090000,0.98,-0.0079,-0.012,0.18,0.015,-0.0077,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00075,-0.0018,-0.14,0.2,-2.4e-06,0.43,1.5e-05,2.6e-05,-0.0003,0,0,-4.9e+02,0.00065,0.00061,0.038,0.052,0.059,0.014,0.052,0.054,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13190000,0.98,-0.0079,-0.012,0.18,0.0097,-0.0078,0.017,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00053,-0.0023,-0.14,0.2,-2.6e-06,0.43,3.9e-05,2.4e-05,-0.00031,0,0,-4.9e+02,0.00061,0.00058,0.038,0.044,0.05,0.013,0.046,0.047,0.048,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13290000,0.98,-0.008,-0.012,0.18,0.011,-0.0095,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00076,-0.0028,-0.14,0.2,-2.4e-06,0.43,4.8e-05,4.4e-05,-0.00031,0,0,-4.9e+02,0.00061,0.00058,0.038,0.049,0.056,0.013,0.052,0.054,0.048,3.6e-06,3e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13390000,0.98,-0.0079,-0.012,0.18,0.0091,-0.0081,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0014,-0.0028,-0.14,0.2,-2.7e-06,0.43,8.6e-05,4.2e-05,-0.00035,0,0,-4.9e+02,0.00057,0.00056,0.038,0.042,0.047,0.012,0.045,0.046,0.047,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13490000,0.98,-0.0079,-0.012,0.18,0.011,-0.0068,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0015,-0.0033,-0.14,0.2,-2.6e-06,0.43,8.9e-05,6.4e-05,-0.00035,0,0,-4.9e+02,0.00058,0.00056,0.038,0.047,0.052,0.011,0.052,0.053,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13590000,0.98,-0.0079,-0.012,0.18,0.014,-0.0071,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.002,-0.0034,-0.14,0.2,-2.6e-06,0.43,9.8e-05,5.7e-05,-0.00035,0,0,-4.9e+02,0.00054,0.00053,0.038,0.04,0.044,0.011,0.045,0.046,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13690000,0.98,-0.0078,-0.012,0.18,0.014,-0.0082,0.015,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0016,-0.0031,-0.14,0.2,-2.6e-06,0.43,8.5e-05,3.7e-05,-0.00033,0,0,-4.9e+02,0.00055,0.00053,0.038,0.044,0.049,0.011,0.052,0.053,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13790000,0.98,-0.0077,-0.012,0.18,0.019,-0.0044,0.015,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0022,-0.0026,-0.14,0.2,-2.8e-06,0.43,8.3e-05,1.6e-05,-0.00034,0,0,-4.9e+02,0.00052,0.00051,0.038,0.038,0.042,0.01,0.045,0.046,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13890000,0.98,-0.0076,-0.012,0.18,0.019,-0.0029,0.016,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0015,-0.002,-0.14,0.2,-3e-06,0.43,6.2e-05,3.3e-07,-0.00034,0,0,-4.9e+02,0.00052,0.00052,0.038,0.042,0.046,0.01,0.051,0.053,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13990000,0.98,-0.0076,-0.012,0.18,0.019,-0.001,0.014,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.001,-0.0025,-0.14,0.2,-2.9e-06,0.43,7e-05,-9.3e-07,-0.00031,0,0,-4.9e+02,0.0005,0.0005,0.038,0.036,0.039,0.0097,0.045,0.046,0.043,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -14090000,0.98,-0.0077,-0.011,0.18,0.017,-0.0082,0.015,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0028,-0.0023,-0.14,0.2,-2.8e-06,0.43,0.00012,7.3e-06,-0.00035,0,0,-4.9e+02,0.0005,0.0005,0.038,0.04,0.043,0.0096,0.051,0.053,0.042,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14190000,0.98,-0.0078,-0.011,0.18,0.016,-0.0076,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0039,-0.0034,-0.14,0.2,-2.6e-06,0.43,0.00018,3.3e-05,-0.00037,0,0,-4.9e+02,0.00048,0.00049,0.038,0.034,0.037,0.0094,0.045,0.046,0.042,2.1e-06,1.9e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14290000,0.98,-0.0077,-0.011,0.18,0.018,-0.0081,0.013,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.004,-0.0037,-0.14,0.2,-2.6e-06,0.43,0.00018,3.6e-05,-0.00036,0,0,-4.9e+02,0.00048,0.00049,0.038,0.038,0.041,0.0092,0.051,0.052,0.041,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14390000,0.98,-0.0078,-0.011,0.18,0.018,-0.0095,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0038,-0.0044,-0.14,0.2,-2.4e-06,0.43,0.00019,4.1e-05,-0.00035,0,0,-4.9e+02,0.00047,0.00047,0.038,0.033,0.035,0.009,0.045,0.046,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14490000,0.98,-0.008,-0.011,0.18,0.018,-0.011,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0049,-0.0045,-0.14,0.2,-2.3e-06,0.43,0.00022,5e-05,-0.00037,0,0,-4.9e+02,0.00047,0.00047,0.038,0.036,0.038,0.009,0.051,0.052,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14590000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00015,-0.0054,-0.0058,-0.14,0.2,-2.1e-06,0.43,0.00027,6.9e-05,-0.00037,0,0,-4.9e+02,0.00046,0.00046,0.038,0.031,0.033,0.0088,0.045,0.045,0.04,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14690000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0053,-0.0062,-0.14,0.2,-2e-06,0.43,0.00027,7.6e-05,-0.00037,0,0,-4.9e+02,0.00046,0.00046,0.038,0.034,0.036,0.0088,0.05,0.051,0.039,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14790000,0.98,-0.0082,-0.011,0.18,0.019,-0.0034,0.016,0,0,-4.9e+02,-0.0011,-0.0058,-0.00014,-0.0047,-0.0076,-0.14,0.2,-2.2e-06,0.43,0.00027,7.4e-05,-0.00035,0,0,-4.9e+02,0.00044,0.00045,0.038,0.03,0.031,0.0086,0.044,0.045,0.039,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14890000,0.98,-0.0082,-0.011,0.18,0.021,-0.0055,0.02,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.0093,-0.14,0.2,-1.8e-06,0.43,0.00027,9.5e-05,-0.00031,0,0,-4.9e+02,0.00045,0.00045,0.038,0.032,0.034,0.0087,0.05,0.051,0.039,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -14990000,0.98,-0.0083,-0.011,0.18,0.02,-0.0057,0.022,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0041,-0.011,-0.14,0.2,-1.6e-06,0.43,0.0003,0.00012,-0.00029,0,0,-4.9e+02,0.00044,0.00045,0.038,0.028,0.03,0.0085,0.044,0.045,0.038,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15090000,0.98,-0.0083,-0.011,0.18,0.021,-0.0049,0.026,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00013,-0.00029,0,0,-4.9e+02,0.00044,0.00045,0.038,0.031,0.032,0.0085,0.05,0.051,0.038,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15190000,0.98,-0.0085,-0.011,0.18,0.019,-0.0059,0.027,0,0,-4.9e+02,-0.0011,-0.0058,-0.00014,-0.0048,-0.012,-0.14,0.2,-1.4e-06,0.43,0.00034,0.00014,-0.00029,0,0,-4.9e+02,0.00043,0.00044,0.038,0.027,0.028,0.0085,0.044,0.045,0.038,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15290000,0.98,-0.0086,-0.012,0.18,0.022,-0.0065,0.026,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.2e-06,0.43,0.00033,0.00017,-0.00027,0,0,-4.9e+02,0.00043,0.00044,0.038,0.029,0.031,0.0085,0.049,0.05,0.037,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15390000,0.98,-0.0088,-0.011,0.18,0.021,-0.004,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0045,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,-4.9e+02,0.00042,0.00043,0.038,0.026,0.027,0.0084,0.044,0.044,0.037,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15490000,0.98,-0.0088,-0.011,0.18,0.022,-0.0067,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0046,-0.014,-0.14,0.2,-1.4e-06,0.43,0.00037,0.00019,-0.00029,0,0,-4.9e+02,0.00042,0.00043,0.038,0.028,0.029,0.0085,0.049,0.05,0.037,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15590000,0.98,-0.0088,-0.011,0.18,0.023,-0.0081,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00036,0.00019,-0.00028,0,0,-4.9e+02,0.00041,0.00043,0.038,0.024,0.026,0.0084,0.043,0.044,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15690000,0.98,-0.0086,-0.011,0.18,0.024,-0.01,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0032,-0.012,-0.14,0.2,-1.8e-06,0.43,0.00031,0.00013,-0.00026,0,0,-4.9e+02,0.00041,0.00043,0.038,0.026,0.028,0.0085,0.049,0.049,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15790000,0.98,-0.0086,-0.011,0.18,0.019,-0.0094,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0021,-0.012,-0.14,0.2,-2.2e-06,0.43,0.0003,0.00012,-0.00026,0,0,-4.9e+02,0.00041,0.00042,0.038,0.023,0.025,0.0084,0.043,0.044,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15890000,0.98,-0.0087,-0.011,0.18,0.02,-0.0085,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0031,-0.012,-0.14,0.2,-1.9e-06,0.43,0.00034,0.00015,-0.00027,0,0,-4.9e+02,0.00041,0.00042,0.038,0.025,0.027,0.0085,0.048,0.049,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15990000,0.98,-0.0086,-0.011,0.18,0.018,-0.0074,0.022,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0034,-0.014,-0.14,0.2,-2.1e-06,0.43,0.00038,0.00019,-0.00029,0,0,-4.9e+02,0.0004,0.00042,0.038,0.022,0.024,0.0084,0.043,0.043,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -16090000,0.98,-0.0087,-0.011,0.18,0.019,-0.0092,0.02,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.004,-0.014,-0.14,0.2,-2e-06,0.43,0.00041,0.00021,-0.00031,0,0,-4.9e+02,0.0004,0.00042,0.038,0.024,0.025,0.0085,0.048,0.049,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16190000,0.98,-0.0086,-0.011,0.18,0.015,-0.0076,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0047,-0.015,-0.13,0.2,-2e-06,0.43,0.00044,0.00021,-0.00033,0,0,-4.9e+02,0.0004,0.00041,0.038,0.021,0.023,0.0084,0.043,0.043,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16290000,0.98,-0.0087,-0.011,0.18,0.016,-0.009,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0044,-0.014,-0.13,0.2,-2e-06,0.43,0.00043,0.0002,-0.00032,0,0,-4.9e+02,0.0004,0.00041,0.038,0.023,0.024,0.0085,0.047,0.048,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16390000,0.98,-0.0087,-0.011,0.18,0.019,-0.0081,0.018,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.004,-0.017,-0.13,0.2,-1.7e-06,0.43,0.00045,0.00024,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.021,0.022,0.0084,0.042,0.043,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16490000,0.98,-0.0089,-0.011,0.18,0.022,-0.01,0.021,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0044,-0.017,-0.13,0.2,-1.5e-06,0.43,0.00046,0.00025,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.022,0.023,0.0085,0.047,0.048,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16590000,0.98,-0.0089,-0.011,0.18,0.025,-0.01,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0043,-0.018,-0.13,0.2,-1.7e-06,0.43,0.00048,0.00025,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.02,0.021,0.0084,0.042,0.043,0.036,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16690000,0.98,-0.0089,-0.011,0.18,0.028,-0.015,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0037,-0.017,-0.13,0.2,-1.9e-06,0.43,0.00046,0.00024,-0.0003,0,0,-4.9e+02,0.00039,0.00041,0.038,0.021,0.023,0.0085,0.047,0.047,0.036,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16790000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0031,-0.017,-0.13,0.2,-2.2e-06,0.43,0.00046,0.00024,-0.00029,0,0,-4.9e+02,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.042,0.042,0.036,1e-06,9.3e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16890000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0021,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00043,0.00023,-0.00028,0,0,-4.9e+02,0.00038,0.0004,0.038,0.02,0.022,0.0085,0.046,0.047,0.036,1e-06,9.2e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -16990000,0.98,-0.0088,-0.011,0.18,0.026,-0.013,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,-0.0018,-0.018,-0.13,0.2,-2.3e-06,0.43,0.00044,0.00025,-0.00028,0,0,-4.9e+02,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,1e-06,9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17090000,0.98,-0.0089,-0.011,0.18,0.03,-0.017,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0022,-0.019,-0.13,0.2,-2.4e-06,0.43,0.00048,0.00032,-0.00029,0,0,-4.9e+02,0.00038,0.0004,0.038,0.02,0.021,0.0085,0.046,0.047,0.035,9.9e-07,8.9e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17190000,0.98,-0.009,-0.011,0.18,0.028,-0.021,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0031,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00053,0.00033,-0.00033,0,0,-4.9e+02,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,9.6e-07,8.7e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17290000,0.98,-0.009,-0.011,0.18,0.03,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0038,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00055,0.00034,-0.00035,0,0,-4.9e+02,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.045,0.046,0.036,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17390000,0.98,-0.0089,-0.011,0.18,0.025,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0025,-0.018,-0.13,0.2,-3.2e-06,0.43,0.00053,0.00034,-0.00034,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.041,0.041,0.035,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17490000,0.98,-0.009,-0.011,0.18,0.024,-0.025,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0028,-0.019,-0.13,0.2,-3.2e-06,0.43,0.00054,0.00034,-0.00035,0,0,-4.9e+02,0.00037,0.00039,0.038,0.018,0.02,0.0085,0.045,0.046,0.036,9.3e-07,8.3e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17590000,0.98,-0.0089,-0.011,0.18,0.021,-0.022,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0024,-0.019,-0.13,0.2,-3.8e-06,0.43,0.00055,0.00034,-0.00035,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.04,0.041,0.035,9e-07,8.1e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17690000,0.98,-0.009,-0.011,0.18,0.022,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0021,-0.019,-0.13,0.2,-3.5e-06,0.43,0.00053,0.00032,-0.00033,0,0,-4.9e+02,0.00037,0.00039,0.038,0.018,0.019,0.0084,0.045,0.045,0.035,9e-07,8e-07,2e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17790000,0.98,-0.0091,-0.011,0.18,0.022,-0.022,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00013,-0.0013,-0.019,-0.13,0.2,-3.5e-06,0.43,0.00051,0.00029,-0.00031,0,0,-4.9e+02,0.00037,0.00039,0.038,0.016,0.017,0.0084,0.04,0.041,0.036,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17890000,0.98,-0.0089,-0.011,0.18,0.025,-0.024,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00075,-0.018,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.0003,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.019,0.0084,0.044,0.045,0.036,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17990000,0.98,-0.0089,-0.011,0.18,0.025,-0.02,0.024,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,4.1e-05,-0.02,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.00029,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0083,0.04,0.041,0.035,8.5e-07,7.6e-07,2e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -18090000,0.98,-0.009,-0.011,0.18,0.026,-0.021,0.024,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,8.7e-05,-0.02,-0.13,0.2,-3.3e-06,0.43,0.00048,0.00027,-0.00028,0,0,-4.9e+02,0.00036,0.00038,0.038,0.017,0.018,0.0083,0.044,0.045,0.036,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18190000,0.98,-0.0091,-0.011,0.18,0.025,-0.019,0.024,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0017,-0.021,-0.13,0.2,-3.6e-06,0.43,0.00045,0.00029,-0.00025,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0082,0.04,0.04,0.035,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18290000,0.98,-0.0092,-0.011,0.18,0.028,-0.02,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0018,-0.022,-0.13,0.2,-3.4e-06,0.43,0.00045,0.0003,-0.00024,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.018,0.0082,0.044,0.044,0.036,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18390000,0.98,-0.0091,-0.011,0.18,0.027,-0.019,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.002,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00046,0.00031,-0.00025,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18490000,0.98,-0.0091,-0.011,0.18,0.031,-0.019,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0027,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00045,0.00031,-0.00024,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0082,0.043,0.044,0.036,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18590000,0.98,-0.0089,-0.011,0.18,0.028,-0.019,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0029,-0.021,-0.13,0.2,-4.2e-06,0.43,0.00044,0.00028,-0.00024,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18690000,0.98,-0.0088,-0.011,0.18,0.028,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0039,-0.02,-0.13,0.2,-4.2e-06,0.43,0.00041,0.00025,-0.00022,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0081,0.043,0.044,0.035,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18790000,0.98,-0.0087,-0.011,0.18,0.026,-0.017,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0043,-0.02,-0.13,0.2,-4.6e-06,0.43,0.00041,0.00026,-0.00023,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.008,0.039,0.04,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18890000,0.98,-0.0088,-0.011,0.18,0.026,-0.018,0.018,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0041,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00043,0.00028,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.044,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -18990000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.019,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0049,-0.019,-0.13,0.2,-5.3e-06,0.43,0.00042,0.00027,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.035,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19090000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.0054,-0.019,-0.13,0.2,-5.2e-06,0.43,0.00041,0.00027,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.008,0.042,0.043,0.036,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19190000,0.98,-0.0086,-0.011,0.18,0.02,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0052,-0.019,-0.13,0.2,-6e-06,0.43,0.00043,0.00028,-0.00026,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19290000,0.98,-0.0086,-0.011,0.18,0.021,-0.019,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0052,-0.019,-0.13,0.2,-5.9e-06,0.43,0.00044,0.00029,-0.00026,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.016,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0058,-0.019,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00028,-0.00026,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,6.9e-07,6.2e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19490000,0.98,-0.0088,-0.011,0.18,0.02,-0.017,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0052,-0.02,-0.13,0.2,-6e-06,0.43,0.00043,0.00026,-0.00025,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,6.9e-07,6.1e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19590000,0.98,-0.0087,-0.011,0.18,0.018,-0.019,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0054,-0.02,-0.13,0.2,-6.2e-06,0.43,0.00043,0.00026,-0.00025,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.015,0.0076,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.03,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19690000,0.98,-0.0088,-0.011,0.18,0.018,-0.017,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0059,-0.021,-0.13,0.2,-5.9e-06,0.43,0.00043,0.00026,-0.00024,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.016,0.0076,0.042,0.043,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19790000,0.98,-0.0089,-0.011,0.18,0.015,-0.016,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0059,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19890000,0.98,-0.0089,-0.011,0.18,0.017,-0.016,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0059,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19990000,0.98,-0.0089,-0.012,0.18,0.015,-0.016,0.018,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0068,-0.021,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.038,0.038,0.035,6.4e-07,5.7e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.019,0.019,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.007,-0.021,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00028,-0.00026,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.4e-07,5.6e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5.1 -20190000,0.98,-0.0089,-0.012,0.18,0.017,-0.016,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00013,0.007,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00043,0.0003,-0.00027,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20290000,0.98,-0.009,-0.012,0.18,0.015,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.007,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00043,0.0003,-0.00028,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20390000,0.98,-0.0089,-0.012,0.18,0.013,-0.016,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.008,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00041,0.00028,-0.00026,0,0,-4.9e+02,0.00034,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20490000,0.98,-0.0089,-0.012,0.18,0.0094,-0.017,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0081,-0.022,-0.13,0.2,-7.3e-06,0.43,0.00041,0.00027,-0.00026,0,0,-4.9e+02,0.00034,0.00035,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20590000,0.98,-0.0088,-0.012,0.18,0.0087,-0.017,0.02,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0093,-0.022,-0.13,0.2,-7.2e-06,0.43,0.00039,0.00025,-0.00025,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20690000,0.98,-0.0088,-0.012,0.18,0.0076,-0.017,0.021,0,0,-4.9e+02,-0.0013,-0.0058,-0.00012,0.009,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00039,0.00025,-0.00025,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.015,0.0072,0.041,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20790000,0.98,-0.0081,-0.012,0.18,0.0037,-0.013,0.006,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0098,-0.022,-0.13,0.2,-7.8e-06,0.43,0.00038,0.00025,-0.00025,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.8e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20890000,0.98,0.00097,-0.0077,0.18,-0.00018,-0.002,-0.11,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00038,-0.00019,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.015,0.0071,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20990000,0.98,0.0044,-0.0043,0.18,-0.012,0.017,-0.25,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00036,-0.00015,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.007,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21090000,0.98,0.0027,-0.0047,0.18,-0.024,0.032,-0.37,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-6.9e-06,0.43,0.00043,0.00016,-0.00019,0,0,-4.9e+02,0.00033,0.00035,0.038,0.014,0.015,0.007,0.04,0.041,0.035,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21190000,0.98,-6.9e-05,-0.0063,0.18,-0.03,0.039,-0.5,0,0,-4.9e+02,-0.0013,-0.0058,-0.0001,0.0099,-0.024,-0.13,0.2,-6.2e-06,0.43,0.00044,0.00019,-0.00018,0,0,-4.9e+02,0.00033,0.00034,0.038,0.013,0.014,0.0069,0.037,0.038,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21290000,0.98,-0.0023,-0.0076,0.18,-0.029,0.041,-0.63,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0095,-0.024,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00023,-0.00011,0,0,-4.9e+02,0.00033,0.00034,0.037,0.014,0.015,0.0069,0.04,0.041,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21390000,0.98,-0.0037,-0.0082,0.18,-0.026,0.038,-0.75,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,0.0096,-0.024,-0.13,0.2,-6.3e-06,0.43,0.00044,0.00015,-0.00012,0,0,-4.9e+02,0.00032,0.00034,0.037,0.013,0.014,0.0068,0.037,0.038,0.034,5.3e-07,4.7e-07,1.7e-06,0.031,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21490000,0.98,-0.0045,-0.0086,0.18,-0.021,0.035,-0.89,0,0,-4.9e+02,-0.0013,-0.0058,-0.0001,0.01,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00044,0.00018,-0.00017,0,0,-4.9e+02,0.00032,0.00034,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21590000,0.98,-0.0049,-0.0086,0.18,-0.015,0.032,-1,0,0,-4.9e+02,-0.0013,-0.0058,-9.5e-05,0.01,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00042,0.00023,-0.00018,0,0,-4.9e+02,0.00032,0.00034,0.037,0.013,0.015,0.0067,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21690000,0.98,-0.0052,-0.0085,0.18,-0.012,0.027,-1.1,0,0,-4.9e+02,-0.0013,-0.0058,-8.7e-05,0.011,-0.024,-0.13,0.2,-6.3e-06,0.43,0.00039,0.00027,-0.00017,0,0,-4.9e+02,0.00032,0.00034,0.037,0.014,0.016,0.0067,0.04,0.041,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21790000,0.98,-0.0055,-0.0086,0.18,-0.0066,0.022,-1.3,0,0,-4.9e+02,-0.0013,-0.0058,-7.8e-05,0.012,-0.023,-0.13,0.2,-6.3e-06,0.43,0.00039,0.00027,-0.00022,0,0,-4.9e+02,0.00032,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21890000,0.98,-0.0058,-0.0088,0.18,-0.003,0.017,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-8.1e-05,0.012,-0.023,-0.13,0.2,-6.7e-06,0.43,0.00037,0.00029,-0.00021,0,0,-4.9e+02,0.00032,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21990000,0.98,-0.0064,-0.009,0.18,-0.00094,0.013,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-7.5e-05,0.012,-0.022,-0.13,0.2,-6.4e-06,0.43,0.0004,0.0003,-0.00023,0,0,-4.9e+02,0.00031,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22090000,0.98,-0.0071,-0.0099,0.18,0.0011,0.0095,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.6e-05,0.012,-0.022,-0.13,0.2,-6.3e-06,0.43,0.00039,0.00032,-0.00024,0,0,-4.9e+02,0.00031,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22190000,0.98,-0.0075,-0.01,0.18,0.0069,0.0051,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.8e-05,0.013,-0.02,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00033,-0.00024,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.014,0.0065,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22290000,0.98,-0.0082,-0.01,0.18,0.013,-0.00055,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6e-05,0.013,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00033,-0.00023,0,0,-4.9e+02,0.00031,0.00032,0.037,0.014,0.015,0.0065,0.04,0.041,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22390000,0.98,-0.0085,-0.01,0.18,0.017,-0.0091,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.2e-05,0.012,-0.02,-0.13,0.2,-6.5e-06,0.43,0.00041,0.00033,-0.00026,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.014,0.0064,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22490000,0.98,-0.0087,-0.011,0.18,0.021,-0.016,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.6e-05,0.011,-0.02,-0.13,0.2,-6.9e-06,0.43,0.00041,0.00035,-0.00028,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22590000,0.98,-0.0086,-0.012,0.18,0.029,-0.024,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.8e-05,0.012,-0.02,-0.13,0.2,-6.4e-06,0.43,0.00042,0.00037,-0.00027,0,0,-4.9e+02,0.0003,0.00032,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.028,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6e-05,0.011,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00042,0.00037,-0.00029,0,0,-4.9e+02,0.0003,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.036,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.4e-05,0.011,-0.021,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00034,-0.00031,0,0,-4.9e+02,0.0003,0.00031,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22890000,0.98,-0.0087,-0.012,0.18,0.042,-0.041,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.5e-05,0.011,-0.021,-0.13,0.2,-6.2e-06,0.43,0.00041,0.00035,-0.00029,0,0,-4.9e+02,0.0003,0.00031,0.037,0.013,0.015,0.0063,0.04,0.041,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.046,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.6e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00032,-0.00027,0,0,-4.9e+02,0.0003,0.00031,0.037,0.012,0.014,0.0062,0.036,0.038,0.033,4.3e-07,3.9e-07,1.6e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23090000,0.98,-0.0086,-0.013,0.18,0.051,-0.05,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00039,0.00033,-0.00025,0,0,-4.9e+02,0.0003,0.00031,0.037,0.013,0.014,0.0062,0.04,0.041,0.033,4.3e-07,3.9e-07,1.5e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23190000,0.98,-0.0086,-0.013,0.18,0.057,-0.052,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.9e-05,0.012,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00037,0.0003,-0.00025,0,0,-4.9e+02,0.00029,0.00031,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23290000,0.98,-0.0091,-0.014,0.18,0.062,-0.057,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.012,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00034,0.00034,-0.00025,0,0,-4.9e+02,0.00029,0.00031,0.037,0.013,0.014,0.0062,0.039,0.041,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23390000,0.98,-0.009,-0.014,0.18,0.066,-0.06,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.9e-05,0.012,-0.019,-0.13,0.2,-7.7e-06,0.43,0.00035,0.00032,-0.00023,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23490000,0.98,-0.0091,-0.014,0.18,0.072,-0.062,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.1e-05,0.012,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00034,0.00037,-0.00028,0,0,-4.9e+02,0.00029,0.0003,0.037,0.013,0.014,0.0061,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23590000,0.98,-0.0093,-0.014,0.18,0.075,-0.064,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.7e-05,0.013,-0.019,-0.13,0.2,-8.4e-06,0.43,0.00029,0.00034,-0.00024,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.006,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23690000,0.98,-0.01,-0.015,0.18,0.074,-0.066,-1.3,0,0,-4.9e+02,-0.0013,-0.0058,-3.9e-05,0.013,-0.02,-0.13,0.2,-8.2e-06,0.43,0.00027,0.00036,-0.00024,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.014,0.006,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23790000,0.98,-0.012,-0.017,0.18,0.068,-0.062,-0.95,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.014,-0.02,-0.13,0.2,-7.9e-06,0.43,0.00026,0.00039,-0.00022,0,0,-4.9e+02,0.00029,0.0003,0.037,0.011,0.013,0.006,0.036,0.037,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23890000,0.98,-0.015,-0.021,0.18,0.064,-0.062,-0.52,0,0,-4.9e+02,-0.0013,-0.0058,-3.5e-05,0.014,-0.02,-0.13,0.2,-7.9e-06,0.43,0.00024,0.00042,-0.00024,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.006,0.039,0.041,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23990000,0.98,-0.017,-0.024,0.18,0.063,-0.061,-0.13,0,0,-4.9e+02,-0.0013,-0.0058,-4.2e-05,0.015,-0.02,-0.13,0.2,-8e-06,0.43,0.00021,0.00043,3.6e-06,0,0,-4.9e+02,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.033,3.9e-07,3.5e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24090000,0.98,-0.017,-0.023,0.18,0.07,-0.069,0.099,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.015,-0.019,-0.13,0.2,-8e-06,0.43,0.00022,0.0004,3.6e-06,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24190000,0.98,-0.014,-0.019,0.18,0.08,-0.074,0.089,0,0,-4.9e+02,-0.0013,-0.0058,-4.5e-05,0.017,-0.02,-0.13,0.2,-7.6e-06,0.43,0.00022,0.00037,0.0001,0,0,-4.9e+02,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.032,3.8e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24290000,0.98,-0.012,-0.016,0.18,0.084,-0.078,0.067,0,0,-4.9e+02,-0.0013,-0.0058,-4.3e-05,0.017,-0.02,-0.13,0.2,-7.2e-06,0.43,0.00026,0.00032,9.8e-05,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24390000,0.98,-0.011,-0.015,0.18,0.077,-0.073,0.083,0,0,-4.9e+02,-0.0013,-0.0058,-4.1e-05,0.018,-0.02,-0.13,0.2,-5.9e-06,0.43,0.00025,0.00037,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24490000,0.98,-0.011,-0.015,0.18,0.073,-0.069,0.081,0,0,-4.9e+02,-0.0013,-0.0058,-2.8e-05,0.019,-0.021,-0.13,0.2,-5.9e-06,0.43,0.00017,0.00047,0.00021,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24590000,0.98,-0.012,-0.015,0.18,0.069,-0.066,0.077,0,0,-4.9e+02,-0.0013,-0.0058,-3.9e-05,0.02,-0.021,-0.13,0.2,-4.6e-06,0.43,0.00021,0.00044,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24690000,0.98,-0.012,-0.015,0.18,0.067,-0.065,0.076,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.02,-0.021,-0.13,0.2,-4.8e-06,0.43,0.0002,0.00047,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24790000,0.98,-0.012,-0.014,0.18,0.064,-0.063,0.068,0,0,-4.9e+02,-0.0014,-0.0058,-4.5e-05,0.022,-0.022,-0.13,0.2,-4.2e-06,0.43,0.00019,0.00048,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24890000,0.98,-0.012,-0.014,0.18,0.063,-0.067,0.057,0,0,-4.9e+02,-0.0014,-0.0058,-4e-05,0.022,-0.022,-0.13,0.2,-4e-06,0.43,0.00019,0.00049,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24990000,0.98,-0.012,-0.014,0.18,0.055,-0.063,0.05,0,0,-4.9e+02,-0.0014,-0.0058,-5.4e-05,0.023,-0.023,-0.13,0.2,-4.2e-06,0.43,0.00015,0.00059,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25090000,0.98,-0.012,-0.014,0.18,0.051,-0.063,0.048,0,0,-4.9e+02,-0.0014,-0.0058,-5.4e-05,0.024,-0.023,-0.13,0.2,-4.8e-06,0.43,0.00014,0.00067,0.00029,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25190000,0.98,-0.012,-0.014,0.18,0.045,-0.057,0.048,0,0,-4.9e+02,-0.0014,-0.0058,-7.2e-05,0.025,-0.024,-0.13,0.2,-4.8e-06,0.43,0.00012,0.0007,0.00028,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25290000,0.98,-0.012,-0.013,0.18,0.041,-0.059,0.043,0,0,-4.9e+02,-0.0014,-0.0058,-7.9e-05,0.025,-0.024,-0.13,0.2,-5.4e-06,0.43,0.00011,0.00072,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25390000,0.98,-0.012,-0.013,0.18,0.032,-0.052,0.041,0,0,-4.9e+02,-0.0014,-0.0058,-9.4e-05,0.027,-0.025,-0.13,0.2,-6.2e-06,0.43,7.1e-05,0.00078,0.00026,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25490000,0.98,-0.013,-0.013,0.18,0.028,-0.053,0.041,0,0,-4.9e+02,-0.0014,-0.0058,-9.6e-05,0.026,-0.025,-0.13,0.2,-5.9e-06,0.43,6.5e-05,0.00073,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25590000,0.98,-0.013,-0.012,0.18,0.023,-0.049,0.042,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-6.7e-06,0.43,3.4e-05,0.00076,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25690000,0.98,-0.012,-0.012,0.18,0.023,-0.048,0.031,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-6.8e-06,0.43,4e-05,0.00079,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25790000,0.98,-0.012,-0.012,0.18,0.011,-0.04,0.031,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.029,-0.026,-0.13,0.2,-7.3e-06,0.43,-2.1e-05,0.00072,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25890000,0.98,-0.012,-0.012,0.18,0.0059,-0.039,0.033,0,0,-4.9e+02,-0.0014,-0.0058,-0.00013,0.029,-0.026,-0.13,0.2,-7.5e-06,0.43,-4e-05,0.00069,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25990000,0.98,-0.012,-0.012,0.18,-0.0031,-0.032,0.027,0,0,-4.9e+02,-0.0014,-0.0058,-0.00015,0.031,-0.026,-0.13,0.2,-8.9e-06,0.43,-9.5e-05,0.00067,0.00014,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26090000,0.98,-0.012,-0.012,0.18,-0.0077,-0.032,0.025,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.031,-0.027,-0.13,0.2,-8.4e-06,0.43,-9.2e-05,0.00066,0.00017,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26190000,0.98,-0.012,-0.012,0.18,-0.015,-0.025,0.021,0,0,-4.9e+02,-0.0015,-0.0058,-0.00014,0.032,-0.026,-0.13,0.2,-8.7e-06,0.43,-0.00012,0.00066,0.00019,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26290000,0.98,-0.012,-0.013,0.18,-0.015,-0.024,0.015,0,0,-4.9e+02,-0.0015,-0.0058,-0.00015,0.032,-0.027,-0.13,0.2,-9.3e-06,0.43,-0.00012,0.00067,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26390000,0.98,-0.011,-0.013,0.18,-0.021,-0.017,0.019,0,0,-4.9e+02,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1e-05,0.43,-0.00016,0.00065,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26490000,0.98,-0.011,-0.013,0.18,-0.023,-0.015,0.028,0,0,-4.9e+02,-0.0015,-0.0058,-0.00016,0.033,-0.028,-0.13,0.2,-1.1e-05,0.43,-0.00017,0.00068,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26590000,0.98,-0.01,-0.013,0.18,-0.026,-0.0064,0.029,0,0,-4.9e+02,-0.0015,-0.0058,-0.00017,0.033,-0.028,-0.13,0.2,-1.2e-05,0.43,-0.00019,0.0007,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26690000,0.98,-0.01,-0.012,0.18,-0.027,-0.0023,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00021,0.00071,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.0019,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00023,0.00069,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26890000,0.98,-0.0092,-0.012,0.18,-0.04,0.0048,0.022,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.2e-05,0.43,-0.00023,0.00067,0.00011,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.012,0.021,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00065,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27090000,0.98,-0.0086,-0.013,0.18,-0.05,0.018,0.025,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.035,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00065,0.00012,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27190000,0.98,-0.0086,-0.013,0.18,-0.056,0.025,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00026,0.00064,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27290000,0.98,-0.0088,-0.014,0.18,-0.063,0.03,0.14,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00027,0.00064,0.00013,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0054,0.038,0.039,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27390000,0.98,-0.01,-0.016,0.18,-0.07,0.037,0.46,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.5e-05,0.43,-0.00033,0.00057,0.00018,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27490000,0.98,-0.012,-0.018,0.18,-0.074,0.043,0.78,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.0003,0.00053,0.00018,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.013,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27590000,0.98,-0.011,-0.017,0.18,-0.069,0.046,0.87,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00048,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27690000,0.98,-0.01,-0.014,0.18,-0.065,0.042,0.78,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.5e-05,0.43,-0.00027,0.00047,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27790000,0.98,-0.0088,-0.012,0.18,-0.065,0.041,0.77,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00043,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27890000,0.98,-0.0085,-0.013,0.18,-0.071,0.047,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.035,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00043,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27990000,0.98,-0.0089,-0.013,0.18,-0.072,0.049,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00037,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28090000,0.98,-0.0092,-0.013,0.18,-0.076,0.05,0.8,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00039,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28190000,0.98,-0.0086,-0.013,0.18,-0.077,0.047,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.033,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00038,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28290000,0.98,-0.0081,-0.013,0.18,-0.081,0.051,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.00018,0.034,-0.029,-0.12,0.2,-1.5e-05,0.43,-0.00027,0.0004,0.00019,0,0,-4.9e+02,0.00029,0.00029,0.037,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.033,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00031,0.00031,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28490000,0.98,-0.0084,-0.015,0.18,-0.084,0.058,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00028,0.0003,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28590000,0.98,-0.0085,-0.014,0.18,-0.078,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00025,0.00028,0.00022,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28690000,0.98,-0.0082,-0.014,0.18,-0.078,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00022,0.00028,0.00022,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28790000,0.98,-0.0076,-0.014,0.18,-0.076,0.056,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00015,0.032,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.00018,0.00022,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28890000,0.98,-0.0074,-0.013,0.18,-0.08,0.058,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.032,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00025,0.00021,0.0002,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28990000,0.98,-0.0072,-0.013,0.18,-0.077,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.031,-0.029,-0.12,0.2,-1.8e-05,0.43,-0.00028,6.7e-05,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29090000,0.98,-0.007,-0.013,0.18,-0.08,0.057,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.0003,4.9e-05,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29190000,0.98,-0.0069,-0.014,0.18,-0.078,0.056,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.03,-0.029,-0.12,0.2,-2e-05,0.43,-0.00033,-8.1e-05,0.00024,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29290000,0.98,-0.0072,-0.014,0.18,-0.081,0.062,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00032,-0.0001,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29390000,0.98,-0.0076,-0.013,0.18,-0.077,0.061,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00036,-0.00023,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.8e-07,2.6e-07,9.9e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29490000,0.98,-0.0076,-0.013,0.18,-0.08,0.062,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.0001,0.029,-0.028,-0.12,0.2,-2.1e-05,0.43,-0.00038,-0.0002,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29590000,0.98,-0.0075,-0.013,0.18,-0.077,0.061,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-8.6e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00043,-0.00031,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29690000,0.98,-0.0075,-0.013,0.18,-0.082,0.06,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-7.9e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00045,-0.00027,0.00021,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29790000,0.98,-0.0073,-0.013,0.18,-0.079,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-6.3e-05,0.027,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.0005,-0.00039,0.00021,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29890000,0.98,-0.0068,-0.013,0.18,-0.08,0.056,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.7e-05,0.028,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.00052,-0.00036,0.00019,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29990000,0.98,-0.007,-0.013,0.18,-0.075,0.051,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-4.5e-05,0.026,-0.029,-0.12,0.2,-2.6e-05,0.43,-0.00051,-0.00041,0.00021,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.5e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30090000,0.98,-0.0071,-0.013,0.18,-0.077,0.051,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.6e-05,0.026,-0.029,-0.12,0.2,-2.7e-05,0.43,-0.00046,-0.00048,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.4e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30190000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.8e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00046,-0.00069,0.00032,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30290000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.7e-05,0.026,-0.029,-0.12,0.2,-2.8e-05,0.43,-0.0005,-0.00074,0.00032,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30390000,0.98,-0.0071,-0.013,0.18,-0.065,0.043,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-3.9e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00064,-0.00095,0.00032,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30490000,0.98,-0.0071,-0.013,0.18,-0.068,0.043,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-3.3e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00068,-0.00094,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30590000,0.98,-0.0074,-0.014,0.18,-0.064,0.041,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.8e-05,0.024,-0.03,-0.12,0.2,-3e-05,0.43,-0.00079,-0.001,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.1e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30690000,0.98,-0.0078,-0.014,0.18,-0.062,0.04,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.7e-05,0.025,-0.03,-0.12,0.2,-3e-05,0.43,-0.00076,-0.00099,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.5e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30790000,0.98,-0.0075,-0.013,0.17,-0.056,0.034,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.3e-05,0.024,-0.031,-0.12,0.2,-3.1e-05,0.43,-0.00084,-0.0012,0.00033,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30890000,0.98,-0.0069,-0.013,0.17,-0.056,0.031,0.79,0,0,-4.9e+02,-0.0014,-0.0058,-2e-05,0.024,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00075,-0.0011,0.00035,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30990000,0.98,-0.0071,-0.013,0.17,-0.049,0.025,0.8,0,0,-4.9e+02,-0.0014,-0.0057,-1.3e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00078,-0.0012,0.00038,0,0,-4.9e+02,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31090000,0.98,-0.0073,-0.013,0.17,-0.048,0.024,0.79,0,0,-4.9e+02,-0.0014,-0.0057,-1.7e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00073,-0.0012,0.00039,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31190000,0.98,-0.0075,-0.013,0.17,-0.043,0.02,0.8,0,0,-4.9e+02,-0.0013,-0.0057,-1.2e-06,0.023,-0.033,-0.12,0.2,-3.4e-05,0.43,-0.00083,-0.0012,0.00039,0,0,-4.9e+02,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31290000,0.98,-0.0077,-0.014,0.17,-0.04,0.018,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3.9e-06,0.024,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00086,-0.0011,0.00037,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31390000,0.98,-0.0075,-0.013,0.17,-0.035,0.011,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3.2e-06,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.00095,-0.0015,0.00042,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31490000,0.98,-0.0073,-0.014,0.17,-0.036,0.0081,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.5e-06,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.001,-0.0017,0.00043,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31590000,0.98,-0.0071,-0.014,0.17,-0.033,0.0062,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.1e-05,0.023,-0.034,-0.12,0.2,-3.1e-05,0.43,-0.0011,-0.0018,0.00045,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.5e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31690000,0.98,-0.0071,-0.014,0.17,-0.036,0.0056,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.9e-05,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.0012,-0.0018,0.00043,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31790000,0.98,-0.0074,-0.015,0.17,-0.026,0.003,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.4e-05,0.023,-0.034,-0.12,0.2,-3e-05,0.43,-0.0013,-0.0019,0.00045,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31890000,0.99,-0.0071,-0.015,0.17,-0.025,0.0008,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.8e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.002,0.00047,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31990000,0.99,-0.0074,-0.014,0.17,-0.017,-0.00029,0.79,0,0,-4.9e+02,-0.0013,-0.0057,2.5e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0022,0.00053,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32090000,0.99,-0.0077,-0.014,0.17,-0.019,-0.0037,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.6e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0022,0.00054,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32190000,0.99,-0.008,-0.014,0.17,-0.013,-0.0073,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.1e-05,0.024,-0.035,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0024,0.00058,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32290000,0.99,-0.0079,-0.014,0.17,-0.013,-0.0099,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.6e-05,0.024,-0.034,-0.12,0.2,-2.8e-05,0.43,-0.0015,-0.0025,0.00059,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32390000,0.99,-0.008,-0.015,0.17,-0.0063,-0.012,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.3e-05,0.025,-0.035,-0.12,0.2,-2.6e-05,0.43,-0.0016,-0.0027,0.00065,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32490000,0.99,-0.011,-0.012,0.17,0.018,-0.077,-0.076,0,0,-4.9e+02,-0.0013,-0.0057,1.9e-05,0.025,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0015,-0.0026,0.00064,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.014,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32590000,0.99,-0.011,-0.013,0.17,0.021,-0.079,-0.079,0,0,-4.9e+02,-0.0013,-0.0057,1.9e-05,0.025,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32690000,0.99,-0.011,-0.012,0.17,0.016,-0.085,-0.08,0,0,-4.9e+02,-0.0013,-0.0057,1.8e-05,0.025,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32790000,0.99,-0.011,-0.013,0.17,0.017,-0.084,-0.081,0,0,-4.9e+02,-0.0013,-0.0057,1.6e-05,0.025,-0.035,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0022,0.00078,0,0,-4.9e+02,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32890000,0.99,-0.011,-0.013,0.17,0.017,-0.09,-0.083,0,0,-4.9e+02,-0.0013,-0.0057,2e-05,0.025,-0.035,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0021,0.00079,0,0,-4.9e+02,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32990000,0.98,-0.011,-0.013,0.17,0.017,-0.089,-0.082,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.025,-0.035,-0.12,0.2,-2.3e-05,0.43,-0.0015,-0.002,0.00085,0,0,-4.9e+02,0.00027,0.00027,0.035,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -33090000,0.98,-0.011,-0.013,0.17,0.013,-0.093,-0.079,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.025,-0.035,-0.12,0.2,-2.3e-05,0.43,-0.0015,-0.002,0.00085,0,0,-4.9e+02,0.00027,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -33190000,0.98,-0.01,-0.013,0.17,0.011,-0.094,-0.078,0,0,-4.9e+02,-0.0014,-0.0057,1.3e-05,0.026,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0015,-0.002,0.00088,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 -33290000,0.98,-0.01,-0.013,0.17,0.0073,-0.096,-0.078,0,0,-4.9e+02,-0.0014,-0.0057,2.3e-05,0.026,-0.034,-0.12,0.2,-2e-05,0.43,-0.0016,-0.002,0.00092,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 -33390000,0.98,-0.01,-0.013,0.17,0.0051,-0.09,-0.076,0,0,-4.9e+02,-0.0014,-0.0057,1.6e-05,0.028,-0.033,-0.12,0.2,-1.8e-05,0.43,-0.0016,-0.002,0.00096,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.033 -33490000,0.98,-0.01,-0.013,0.17,-0.00023,-0.093,-0.075,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.028,-0.032,-0.12,0.2,-1.6e-05,0.43,-0.0017,-0.0021,0.00099,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.058 -33590000,0.98,-0.01,-0.013,0.17,-0.003,-0.092,-0.072,0,0,-4.9e+02,-0.0014,-0.0057,2e-05,0.029,-0.032,-0.12,0.2,-1.3e-05,0.43,-0.0018,-0.0022,0.001,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.083 -33690000,0.98,-0.01,-0.013,0.17,-0.0063,-0.095,-0.073,0,0,-4.9e+02,-0.0014,-0.0057,2.4e-05,0.029,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.0018,-0.002,0.001,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.11 -33790000,0.98,-0.01,-0.013,0.17,-0.0082,-0.092,-0.068,0,0,-4.9e+02,-0.0014,-0.0057,1.4e-05,0.031,-0.032,-0.12,0.2,-1.2e-05,0.43,-0.0017,-0.0018,0.0011,0,0,-4.9e+02,0.00027,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.13 -33890000,0.98,-0.01,-0.013,0.17,-0.012,-0.093,-0.067,0,0,-4.9e+02,-0.0014,-0.0057,2.4e-05,0.031,-0.032,-0.12,0.2,-1.1e-05,0.43,-0.0018,-0.0018,0.0011,0,0,-4.9e+02,0.00027,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.4e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.16 -33990000,0.98,-0.0099,-0.013,0.17,-0.013,-0.088,-0.064,0,0,-4.9e+02,-0.0014,-0.0057,1.2e-05,0.033,-0.031,-0.12,0.2,-8.4e-06,0.43,-0.0017,-0.0018,0.0011,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.18 -34090000,0.98,-0.0098,-0.013,0.17,-0.017,-0.093,-0.062,0,0,-4.9e+02,-0.0014,-0.0057,1.5e-05,0.033,-0.031,-0.12,0.2,-8.8e-06,0.43,-0.0017,-0.0017,0.0011,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.21 -34190000,0.98,-0.0098,-0.013,0.17,-0.018,-0.088,-0.06,0,0,-4.9e+02,-0.0014,-0.0057,1e-05,0.035,-0.031,-0.12,0.2,-6.4e-06,0.43,-0.0016,-0.0015,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.23 -34290000,0.98,-0.0096,-0.013,0.17,-0.019,-0.092,-0.058,0,0,-4.9e+02,-0.0014,-0.0057,1.7e-05,0.035,-0.031,-0.12,0.2,-5.7e-06,0.43,-0.0017,-0.0016,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.26 -34390000,0.98,-0.0095,-0.013,0.17,-0.021,-0.085,-0.054,0,0,-4.9e+02,-0.0014,-0.0056,9.9e-06,0.036,-0.03,-0.12,0.2,-3.6e-06,0.43,-0.0016,-0.0015,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.28 -34490000,0.98,-0.0095,-0.013,0.17,-0.024,-0.089,-0.052,0,0,-4.9e+02,-0.0014,-0.0056,1.8e-05,0.036,-0.03,-0.12,0.2,-3.3e-06,0.43,-0.0017,-0.0014,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.31 -34590000,0.98,-0.0094,-0.013,0.17,-0.026,-0.081,0.74,0,0,-4.9e+02,-0.0014,-0.0056,1.1e-05,0.038,-0.03,-0.12,0.2,-8.1e-07,0.43,-0.0016,-0.0014,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 -34690000,0.98,-0.0094,-0.013,0.17,-0.03,-0.079,1.7,0,0,-4.9e+02,-0.0014,-0.0056,1.4e-05,0.038,-0.03,-0.12,0.2,-5.2e-07,0.43,-0.0017,-0.0014,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.36 -34790000,0.98,-0.0093,-0.013,0.17,-0.033,-0.07,2.7,0,0,-4.9e+02,-0.0015,-0.0056,7.9e-06,0.04,-0.031,-0.12,0.2,2.1e-06,0.43,-0.0017,-0.0013,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 -34890000,0.98,-0.0092,-0.013,0.17,-0.038,-0.069,3.7,0,0,-4.9e+02,-0.0015,-0.0056,1.1e-05,0.04,-0.031,-0.12,0.2,2.2e-06,0.43,-0.0017,-0.0013,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 +2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0,0,-4.9e+02,-0.0014,-0.0018,-8.8e-06,0,0,-0.0075,0,0,0,0,0,0,0,0,-4.9e+02,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0,0,-4.9e+02,-0.0014,-0.0018,-8.6e-06,0,0,-0.0097,0,0,0,0,0,0,0,0,-4.9e+02,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0,0,-4.9e+02,-0.0017,-0.0023,-1.5e-05,0,0,-0.012,0,0,0,0,0,0,0,0,-4.9e+02,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.014,0.00048,0.033,-0.0088,-0.14,0,0,-4.9e+02,-0.0017,-0.0023,-1.5e-05,0,0,-0.013,0,0,0,0,0,0,0,0,-4.9e+02,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0,0,-4.9e+02,-0.0018,-0.0027,-2.1e-05,0,0,-0.015,0,0,0,0,0,0,0,0,-4.9e+02,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0,0,-4.9e+02,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,-4.9e+02,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.01,-0.013,0.00038,0.022,-0.0029,-0.14,0,0,-4.9e+02,-0.0019,-0.003,-2.6e-05,0,0,-0.022,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0,0,-4.9e+02,-0.0019,-0.003,-2.6e-05,0,0,-0.025,0,0,0,0,0,0,0,0,-4.9e+02,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.01,-0.013,0.00032,0.02,-0.0035,-0.15,0,0,-4.9e+02,-0.002,-0.0033,-3.1e-05,0,0,-0.028,0,0,0,0,0,0,0,0,-4.9e+02,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0,0,-4.9e+02,-0.002,-0.0033,-3.1e-05,0,0,-0.031,0,0,0,0,0,0,0,0,-4.9e+02,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.01,-0.013,0.00057,0.02,-0.0061,-0.15,0,0,-4.9e+02,-0.002,-0.0036,-3.5e-05,0,0,-0.032,0,0,0,0,0,0,0,0,-4.9e+02,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0,0,-4.9e+02,-0.002,-0.0036,-3.5e-05,0,0,-0.034,0,0,0,0,0,0,0,0,-4.9e+02,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0,0,-4.9e+02,-0.0021,-0.0038,-3.9e-05,0,0,-0.039,0,0,0,0,0,0,0,0,-4.9e+02,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.0097,-0.013,0.00059,0.025,-0.0018,-0.15,0,0,-4.9e+02,-0.0021,-0.0038,-3.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,-4.9e+02,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0,0,-4.9e+02,-0.0022,-0.004,-4.3e-05,0,0,-0.046,0,0,0,0,0,0,0,0,-4.9e+02,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.0095,-0.013,0.00053,0.024,-0.00063,-0.15,0,0,-4.9e+02,-0.0022,-0.004,-4.3e-05,0,0,-0.051,0,0,0,0,0,0,0,0,-4.9e+02,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.0094,-0.012,0.00055,0.019,0.0037,-0.15,0,0,-4.9e+02,-0.0022,-0.0043,-4.8e-05,0,0,-0.054,0,0,0,0,0,0,0,0,-4.9e+02,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.0094,-0.013,0.00064,0.021,0.005,-0.14,0,0,-4.9e+02,-0.0022,-0.0042,-4.7e-05,0,0,-0.058,0,0,0,0,0,0,0,0,-4.9e+02,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0,0,-4.9e+02,-0.0022,-0.0042,-4.7e-05,0,0,-0.063,0,0,0,0,0,0,0,0,-4.9e+02,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.0093,-0.012,0.00077,0.022,0.0042,-0.12,0,0,-4.9e+02,-0.0022,-0.0044,-5.2e-05,0,0,-0.071,0,0,0,0,0,0,0,0,-4.9e+02,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0,0,-4.9e+02,-0.0022,-0.0044,-5.2e-05,0,0,-0.074,0,0,0,0,0,0,0,0,-4.9e+02,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.0095,-0.012,0.00075,0.021,0.0037,-0.13,0,0,-4.9e+02,-0.0021,-0.0046,-5.7e-05,0,0,-0.076,0,0,0,0,0,0,0,0,-4.9e+02,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0,0,-4.9e+02,-0.0021,-0.0046,-5.7e-05,0,0,-0.083,0,0,0,0,0,0,0,0,-4.9e+02,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.0094,-0.012,0.00077,0.021,0.004,-0.11,0,0,-4.9e+02,-0.0021,-0.0048,-6.2e-05,0,0,-0.086,0,0,0,0,0,0,0,0,-4.9e+02,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0,0,-4.9e+02,-0.0021,-0.0048,-6.2e-05,0,0,-0.088,0,0,0,0,0,0,0,0,-4.9e+02,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.0094,-0.012,0.00077,0.017,0.0031,-0.1,0,0,-4.9e+02,-0.0021,-0.005,-6.6e-05,0,0,-0.093,0,0,0,0,0,0,0,0,-4.9e+02,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.0093,-0.012,0.00087,0.015,0.0053,-0.1,0,0,-4.9e+02,-0.0021,-0.005,-6.6e-05,0,0,-0.095,0,0,0,0,0,0,0,0,-4.9e+02,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.0092,-0.012,0.00091,0.01,0.0028,-0.093,0,0,-4.9e+02,-0.0021,-0.0051,-7e-05,0,0,-0.099,0,0,0,0,0,0,0,0,-4.9e+02,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0,0,-4.9e+02,-0.0021,-0.0051,-7e-05,0,0,-0.1,0,0,0,0,0,0,0,0,-4.9e+02,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.0091,-0.011,0.00097,0.01,0.0038,-0.083,0,0,-4.9e+02,-0.002,-0.0052,-7.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,-4.9e+02,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0,0,-4.9e+02,-0.002,-0.0052,-7.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.069,0,0,-4.9e+02,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0,0,-4.9e+02,-0.002,-0.0053,-7.6e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.061,0,0,-4.9e+02,-0.002,-0.0054,-7.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,-4.9e+02,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.054,0,0,-4.9e+02,-0.002,-0.0054,-7.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0089,-0.011,0.0009,0.0077,0.016,-0.053,0,0,-4.9e+02,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0087,-0.011,0.00086,0.0089,0.018,-0.05,0,0,-4.9e+02,-0.0019,-0.0054,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0088,-0.011,0.0009,0.0095,0.016,-0.048,0,0,-4.9e+02,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0088,-0.012,0.00087,0.011,0.017,-0.042,0,0,-4.9e+02,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0087,-0.011,0.00068,0.011,0.018,-0.039,0,0,-4.9e+02,-0.0019,-0.0055,-8.3e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0089,-0.011,0.00069,0.0087,0.017,-0.038,0,0,-4.9e+02,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0088,-0.011,0.00072,0.008,0.02,-0.041,0,0,-4.9e+02,-0.0018,-0.0055,-8.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0089,-0.011,0.00073,0.0082,0.017,-0.042,0,0,-4.9e+02,-0.0017,-0.0056,-8.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,-4.9e+02,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0088,-0.011,0.00063,0.0057,0.016,-0.04,0,0,-4.9e+02,-0.0017,-0.0056,-8.8e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0089,-0.011,0.00056,0.0039,0.015,-0.042,0,0,-4.9e+02,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0088,-0.011,0.00052,0.0022,0.018,-0.044,0,0,-4.9e+02,-0.0017,-0.0056,-9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6790000,1,-0.0089,-0.011,0.00049,0.003,0.016,-0.043,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6890000,1,-0.0087,-0.011,0.0004,0.0023,0.016,-0.039,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,-4.9e+02,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +6990000,0.98,-0.0067,-0.012,0.18,0.0025,0.011,-0.037,0,0,-4.9e+02,-0.0015,-0.0056,-9.4e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,-4.9e+02,0.0012,0.0012,0.054,0.16,0.17,0.031,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 +7090000,0.98,-0.0065,-0.012,0.18,0.00012,0.018,-0.038,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,-4.9e+02,0.0013,0.0013,0.048,0.18,0.19,0.03,0.13,0.13,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7190000,0.98,-0.0065,-0.012,0.18,-6.6e-05,0.019,-0.037,0,0,-4.9e+02,-0.0016,-0.0056,-9.4e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.3e-06,0,0,-4.9e+02,0.0013,0.0013,0.046,0.21,0.21,0.029,0.16,0.16,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7290000,0.98,-0.0064,-0.012,0.18,-0.00068,0.024,-0.034,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,-4.9e+02,0.0014,0.0013,0.044,0.24,0.24,0.028,0.19,0.19,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7390000,0.98,-0.0063,-0.012,0.18,-0.0015,0.00095,-0.032,0,0,-4.9e+02,-0.0016,-0.0057,-9.4e-05,-0.00036,0.00036,-0.13,0.2,-5.7e-05,0.43,-0.00048,-0.0004,8.9e-05,0,0,-4.9e+02,0.0014,0.0014,0.043,25,25,0.027,1e+02,1e+02,0.064,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00027,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7490000,0.98,-0.0063,-0.012,0.18,0.00098,0.0035,-0.026,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-4.5e-05,0.43,-0.00042,-0.00038,-7.8e-05,0,0,-4.9e+02,0.0015,0.0014,0.043,25,25,0.026,1e+02,1e+02,0.063,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00022,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7590000,0.98,-0.0064,-0.012,0.18,0.0021,0.0061,-0.023,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-3.8e-05,0.43,-0.00035,-0.00039,-8.8e-06,0,0,-4.9e+02,0.0015,0.0015,0.042,25,25,0.025,51,51,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00019,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7690000,0.98,-0.0064,-0.013,0.18,0.0021,0.0093,-0.022,0,0,-4.9e+02,-0.0016,-0.0056,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-3.4e-05,0.43,-0.00031,-0.0004,3.2e-06,0,0,-4.9e+02,0.0016,0.0015,0.042,25,25,0.025,52,52,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00017,0.0013,0.0014,0.0016,0.0013,1,1,2 +7790000,0.98,-0.0064,-0.013,0.18,0.0056,0.01,-0.025,0,0,-4.9e+02,-0.0015,-0.0055,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-2.9e-05,0.43,-0.00021,-0.00039,-8.1e-07,0,0,-4.9e+02,0.0016,0.0016,0.042,24,24,0.024,35,35,0.061,6.3e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00015,0.0013,0.0014,0.0016,0.0013,1,1,2 +7890000,0.98,-0.0064,-0.013,0.18,0.0047,0.014,-0.025,0,0,-4.9e+02,-0.0015,-0.0055,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-2.6e-05,0.43,-0.00019,-0.0004,4.5e-05,0,0,-4.9e+02,0.0016,0.0016,0.042,24,24,0.023,36,36,0.06,6.3e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00013,0.0013,0.0014,0.0016,0.0013,1,1,2 +7990000,0.98,-0.0063,-0.013,0.18,0.0032,0.017,-0.022,0,0,-4.9e+02,-0.0016,-0.0056,-9.3e-05,-0.00036,0.00036,-0.13,0.2,-2.5e-05,0.43,-0.0002,-0.00042,7.5e-05,0,0,-4.9e+02,0.0017,0.0016,0.042,24,24,0.022,28,28,0.059,6.2e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00012,0.0013,0.0014,0.0016,0.0013,1,1,2 +8090000,0.98,-0.0062,-0.013,0.18,0.0043,0.019,-0.022,0,0,-4.9e+02,-0.0015,-0.0056,-9.5e-05,-0.00036,0.00036,-0.13,0.2,-2.2e-05,0.43,-0.00017,-0.00042,0.0001,0,0,-4.9e+02,0.0017,0.0017,0.042,24,24,0.022,30,30,0.059,6.2e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,0.00011,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8190000,0.98,-0.0064,-0.012,0.18,0.0053,0.022,-0.018,0,0,-4.9e+02,-0.0015,-0.0056,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.44,-0.00014,-0.00041,0.00015,0,0,-4.9e+02,0.0018,0.0017,0.041,23,23,0.021,24,24,0.058,6.1e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,0.0001,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8290000,0.98,-0.0062,-0.012,0.18,0.002,0.028,-0.017,0,0,-4.9e+02,-0.0015,-0.0058,-9.8e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.43,-0.00014,-0.00044,6.8e-05,0,0,-4.9e+02,0.0018,0.0017,0.041,23,23,0.02,27,27,0.057,6.1e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,9.6e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8390000,0.98,-0.0061,-0.012,0.18,-0.0023,0.028,-0.016,0,0,-4.9e+02,-0.0015,-0.0058,-9.9e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00044,2.1e-05,0,0,-4.9e+02,0.0019,0.0018,0.041,21,21,0.02,23,23,0.057,6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8490000,0.98,-0.0058,-0.012,0.18,-0.0061,0.035,-0.017,0,0,-4.9e+02,-0.0016,-0.0059,-9.8e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00048,-6.7e-06,0,0,-4.9e+02,0.0019,0.0018,0.041,21,21,0.019,25,25,0.056,5.9e-05,5.6e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8590000,0.98,-0.006,-0.012,0.18,-0.0003,0.034,-0.012,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.14,0.2,-1.7e-05,0.43,-0.00018,-0.00043,3.8e-06,0,0,-4.9e+02,0.0019,0.0018,0.041,19,19,0.018,22,22,0.055,5.8e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,7.9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8690000,0.98,-0.0059,-0.012,0.18,-0.0022,0.037,-0.014,0,0,-4.9e+02,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.14,0.2,-1.6e-05,0.43,-0.00022,-0.00045,-8.7e-05,0,0,-4.9e+02,0.002,0.0018,0.041,19,19,0.018,24,24,0.055,5.8e-05,5.3e-05,2.2e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8790000,0.98,-0.0059,-0.012,0.18,-0.005,0.039,-0.014,0,0,-4.9e+02,-0.0016,-0.0058,-9.9e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00019,-0.00045,-0.00013,0,0,-4.9e+02,0.002,0.0018,0.041,19,19,0.018,27,27,0.055,5.7e-05,5.2e-05,2.2e-06,0.04,0.04,0.00099,0.0013,7.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8890000,0.98,-0.006,-0.012,0.18,0.00052,0.041,-0.0094,0,0,-4.9e+02,-0.0016,-0.0057,-9.6e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00026,-0.00043,-0.00011,0,0,-4.9e+02,0.002,0.0018,0.041,17,17,0.017,24,24,0.054,5.6e-05,5e-05,2.2e-06,0.04,0.04,0.00094,0.0013,6.7e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +8990000,0.98,-0.0059,-0.013,0.18,0.01,0.047,-0.0086,0,0,-4.9e+02,-0.0016,-0.0056,-9.1e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00037,-0.00039,-6.6e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,17,17,0.017,27,27,0.054,5.5e-05,4.9e-05,2.2e-06,0.04,0.04,0.00091,0.0013,6.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +9090000,0.98,-0.0055,-0.012,0.18,-0.0004,0.057,-0.0096,0,0,-4.9e+02,-0.0017,-0.0057,-9e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00028,-0.0005,-8.8e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,15,15,0.016,24,24,0.053,5.3e-05,4.7e-05,2.2e-06,0.04,0.04,0.00087,0.0013,6.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +9190000,0.98,-0.0053,-0.013,0.18,0.0028,0.064,-0.009,0,0,-4.9e+02,-0.0018,-0.0057,-8.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00031,-0.00053,-0.00011,0,0,-4.9e+02,0.0021,0.0018,0.041,15,15,0.016,27,27,0.052,5.2e-05,4.5e-05,2.2e-06,0.04,0.04,0.00083,0.0013,5.9e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.3 +9290000,0.98,-0.0052,-0.013,0.18,0.013,0.062,-0.0074,0,0,-4.9e+02,-0.0017,-0.0056,-8.6e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.0004,-0.00049,-8.6e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,13,13,0.015,24,24,0.052,5.1e-05,4.4e-05,2.2e-06,0.04,0.04,0.00079,0.0013,5.6e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 +9390000,0.98,-0.0054,-0.013,0.18,0.014,0.06,-0.0063,0,0,-4.9e+02,-0.0017,-0.0056,-8.9e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00035,-0.00044,-3.9e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,13,13,0.015,26,26,0.052,5e-05,4.2e-05,2.2e-06,0.04,0.04,0.00077,0.0013,5.4e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 +9490000,0.98,-0.0053,-0.013,0.18,0.0085,0.062,-0.0046,0,0,-4.9e+02,-0.0017,-0.0057,-8.9e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00033,-0.00048,-7.7e-05,0,0,-4.9e+02,0.0021,0.0018,0.041,12,12,0.015,23,23,0.051,4.8e-05,4e-05,2.2e-06,0.04,0.04,0.00074,0.0013,5.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 +9590000,0.98,-0.0057,-0.013,0.18,0.0075,0.053,-0.0045,0,0,-4.9e+02,-0.0016,-0.0057,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-1e-05,0.43,-0.0003,-0.00042,-0.00012,0,0,-4.9e+02,0.0022,0.0018,0.041,12,12,0.014,26,26,0.05,4.7e-05,3.9e-05,2.2e-06,0.04,0.04,0.00071,0.0013,5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 +9690000,0.98,-0.0059,-0.013,0.18,0.0093,0.048,-0.0016,0,0,-4.9e+02,-0.0015,-0.0057,-9.7e-05,-0.00036,0.00036,-0.14,0.2,-9.2e-06,0.43,-0.00031,-0.00038,-0.0001,0,0,-4.9e+02,0.0022,0.0018,0.041,10,10,0.014,23,23,0.05,4.6e-05,3.7e-05,2.2e-06,0.04,0.04,0.00068,0.0013,4.8e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9790000,0.98,-0.0061,-0.012,0.18,0.00062,0.042,-0.003,0,0,-4.9e+02,-0.0014,-0.0058,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.8e-06,0.43,-0.00018,-0.00037,-0.00015,0,0,-4.9e+02,0.0022,0.0017,0.041,10,10,0.014,25,25,0.05,4.4e-05,3.5e-05,2.2e-06,0.04,0.04,0.00066,0.0013,4.7e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9890000,0.98,-0.0061,-0.012,0.18,0.0082,0.041,-0.0017,0,0,-4.9e+02,-0.0014,-0.0057,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.6e-06,0.43,-0.00023,-0.00035,-9.7e-05,0,0,-4.9e+02,0.0022,0.0017,0.041,8.6,8.7,0.013,22,22,0.049,4.3e-05,3.4e-05,2.2e-06,0.04,0.04,0.00063,0.0013,4.5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9990000,0.98,-0.0063,-0.012,0.18,0.002,0.034,-0.001,0,0,-4.9e+02,-0.0013,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-6.5e-06,0.43,-0.00013,-0.00033,-0.00013,0,0,-4.9e+02,0.0022,0.0017,0.041,8.6,8.7,0.013,24,24,0.049,4.2e-05,3.2e-05,2.2e-06,0.04,0.04,0.00061,0.0013,4.4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +10090000,0.98,-0.0067,-0.012,0.18,0.00021,0.019,0.00017,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-4.9e-06,0.43,-9.2e-05,-0.00026,-0.00015,0,0,-4.9e+02,0.0022,0.0017,0.041,7.4,7.5,0.013,21,21,0.048,4e-05,3.1e-05,2.2e-06,0.04,0.04,0.00059,0.0013,4.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10190000,0.98,-0.0072,-0.012,0.18,0.0047,0.0051,0.001,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00036,0.00036,-0.14,0.2,-3.3e-06,0.43,-8.4e-05,-0.00012,-0.00015,0,0,-4.9e+02,0.0022,0.0016,0.041,7.4,7.6,0.012,23,23,0.048,3.9e-05,2.9e-05,2.2e-06,0.04,0.04,0.00057,0.0013,4.1e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10290000,0.98,-0.0071,-0.012,0.18,0.011,0.0088,-3.6e-05,0,0,-4.9e+02,-0.0011,-0.0057,-0.00011,-0.00036,0.00036,-0.14,0.2,-3.7e-06,0.43,-0.00015,-0.00011,-0.00012,0,0,-4.9e+02,0.0022,0.0016,0.041,6.4,6.5,0.012,20,20,0.048,3.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10390000,0.98,-0.007,-0.012,0.18,0.0076,0.0026,-0.0025,0,0,-4.9e+02,-0.0011,-0.0057,-0.00011,-0.0003,0.00041,-0.14,0.2,-3.9e-06,0.43,-0.00019,-0.00012,-6.9e-05,0,0,-4.9e+02,0.0022,0.0016,0.041,0.25,0.25,0.56,0.5,0.5,0.048,3.6e-05,2.7e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10490000,0.98,-0.0073,-0.012,0.18,0.0096,0.00086,0.007,0,0,-4.9e+02,-0.001,-0.0057,-0.00012,-0.00034,0.00027,-0.14,0.2,-3e-06,0.43,-0.00016,-6.3e-05,-9.1e-05,0,0,-4.9e+02,0.0021,0.0016,0.041,0.25,0.26,0.55,0.51,0.51,0.057,3.5e-05,2.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10590000,0.98,-0.007,-0.012,0.18,0.00025,-0.00016,0.013,0,0,-4.9e+02,-0.0011,-0.0057,-0.00011,-0.0003,0.00025,-0.14,0.2,-3.6e-06,0.43,-0.00018,-0.0001,-7.7e-05,0,0,-4.9e+02,0.0021,0.0015,0.041,0.13,0.13,0.27,0.17,0.17,0.055,3.3e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10690000,0.98,-0.0071,-0.013,0.18,0.003,-0.0027,0.016,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.00027,0.00018,-0.14,0.2,-3.3e-06,0.43,-0.00021,-5.3e-05,-7.4e-05,0,0,-4.9e+02,0.0021,0.0015,0.041,0.13,0.14,0.26,0.17,0.18,0.065,3.2e-05,2.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10790000,0.98,-0.0073,-0.013,0.18,0.0057,-0.006,0.014,0,0,-4.9e+02,-0.001,-0.0056,-0.00011,-0.00016,7.7e-05,-0.14,0.2,-3.2e-06,0.43,-0.00025,8.2e-06,-9.4e-05,0,0,-4.9e+02,0.002,0.0014,0.041,0.09,0.095,0.17,0.11,0.11,0.061,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10890000,0.98,-0.0069,-0.013,0.18,0.0078,-0.0029,0.01,0,0,-4.9e+02,-0.0011,-0.0055,-0.00011,-5.6e-05,0.0002,-0.14,0.2,-4.1e-06,0.43,-0.00032,-3.5e-05,-7.6e-05,0,0,-4.9e+02,0.002,0.0014,0.041,0.097,0.1,0.16,0.11,0.11,0.068,2.9e-05,2e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +10990000,0.98,-0.0069,-0.013,0.18,0.0053,0.0032,0.016,0,0,-4.9e+02,-0.0011,-0.0056,-0.00011,-0.00021,0.00016,-0.14,0.2,-4.1e-06,0.43,-0.00025,-6.5e-05,-0.00012,0,0,-4.9e+02,0.0019,0.0014,0.041,0.074,0.081,0.12,0.079,0.079,0.065,2.6e-05,1.9e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11090000,0.98,-0.0075,-0.013,0.18,0.0091,0.0017,0.02,0,0,-4.9e+02,-0.001,-0.0056,-0.00011,-0.00029,-4.9e-05,-0.14,0.2,-2.9e-06,0.43,-0.00023,1.9e-05,-0.00011,0,0,-4.9e+02,0.0019,0.0013,0.041,0.082,0.093,0.11,0.084,0.085,0.069,2.6e-05,1.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11190000,0.98,-0.0077,-0.013,0.18,0.0081,0.0023,0.026,0,0,-4.9e+02,-0.00097,-0.0057,-0.00012,-0.00041,8.1e-07,-0.14,0.2,-2.4e-06,0.43,-0.00016,-7.8e-06,-0.00012,0,0,-4.9e+02,0.0017,0.0013,0.04,0.066,0.076,0.084,0.065,0.066,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11290000,0.98,-0.0077,-0.012,0.18,0.0063,-0.00021,0.025,0,0,-4.9e+02,-0.00097,-0.0057,-0.00012,-0.00051,0.00012,-0.14,0.2,-2.3e-06,0.43,-9.5e-05,-4.7e-05,-0.00016,0,0,-4.9e+02,0.0017,0.0012,0.04,0.074,0.088,0.078,0.071,0.072,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11390000,0.98,-0.0076,-0.012,0.18,0.0043,0.00089,0.016,0,0,-4.9e+02,-0.00098,-0.0058,-0.00012,-0.00053,3.9e-05,-0.14,0.2,-2.3e-06,0.43,-7.1e-05,-5.8e-05,-0.00018,0,0,-4.9e+02,0.0015,0.0012,0.04,0.062,0.074,0.064,0.058,0.058,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11490000,0.98,-0.0075,-0.012,0.18,0.005,-0.00059,0.02,0,0,-4.9e+02,-0.00097,-0.0057,-0.00012,-0.00051,-4.3e-05,-0.14,0.2,-2.3e-06,0.43,-9.3e-05,-3.8e-05,-0.00017,0,0,-4.9e+02,0.0015,0.0011,0.04,0.071,0.086,0.058,0.063,0.064,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11590000,0.98,-0.0076,-0.012,0.18,0.0045,-0.00053,0.018,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.00059,5.4e-05,-0.14,0.2,-2.4e-06,0.43,-4.5e-05,-7.8e-05,-0.0002,0,0,-4.9e+02,0.0014,0.0011,0.04,0.06,0.072,0.049,0.053,0.054,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11690000,0.98,-0.0075,-0.012,0.18,0.0039,0.0019,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00055,0.00017,-0.14,0.2,-2.6e-06,0.43,-3.9e-05,-9.5e-05,-0.00022,0,0,-4.9e+02,0.0014,0.001,0.04,0.068,0.084,0.046,0.059,0.06,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11790000,0.98,-0.0075,-0.012,0.18,0.0026,0.0027,0.019,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-1.2e-05,0.00014,-0.14,0.2,-2.7e-06,0.43,-5.3e-05,-0.0001,-0.00023,0,0,-4.9e+02,0.0012,0.00096,0.039,0.058,0.07,0.039,0.05,0.051,0.062,1.3e-05,9.4e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11890000,0.98,-0.0077,-0.012,0.18,0.0037,0.0014,0.017,0,0,-4.9e+02,-0.001,-0.0059,-0.00012,-0.00021,0.0003,-0.14,0.2,-2.5e-06,0.43,-2.3e-05,-0.0001,-0.00026,0,0,-4.9e+02,0.0012,0.00096,0.039,0.066,0.082,0.036,0.056,0.058,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11990000,0.98,-0.0077,-0.012,0.18,0.0065,0.0036,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00027,0.00047,-0.14,0.2,-2.8e-06,0.43,-4.1e-05,-0.00011,-0.00026,0,0,-4.9e+02,0.0011,0.00088,0.039,0.057,0.068,0.032,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +12090000,0.98,-0.0077,-0.012,0.18,0.0096,0.0012,0.017,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.00045,0.00022,-0.14,0.2,-2.5e-06,0.43,-4.1e-05,-7.5e-05,-0.00026,0,0,-4.9e+02,0.0011,0.00088,0.039,0.064,0.079,0.029,0.055,0.056,0.06,1e-05,7.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12190000,0.98,-0.0077,-0.012,0.18,0.011,-5e-06,0.016,0,0,-4.9e+02,-0.00097,-0.0058,-0.00012,-0.0011,-0.00042,-0.14,0.2,-2.4e-06,0.43,-6.2e-06,-4e-05,-0.00028,0,0,-4.9e+02,0.00094,0.00081,0.039,0.055,0.065,0.026,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12290000,0.98,-0.0079,-0.012,0.18,0.0079,-0.0035,0.015,0,0,-4.9e+02,-0.00096,-0.0058,-0.00013,-0.0014,-0.00025,-0.14,0.2,-2.2e-06,0.43,2e-05,-4.9e-05,-0.00028,0,0,-4.9e+02,0.00095,0.00081,0.039,0.062,0.075,0.024,0.054,0.056,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12390000,0.98,-0.0079,-0.012,0.18,0.0078,-0.0047,0.013,0,0,-4.9e+02,-0.00095,-0.0058,-0.00013,-0.0017,-0.00072,-0.14,0.2,-2.2e-06,0.43,4.6e-05,-2.8e-05,-0.0003,0,0,-4.9e+02,0.00085,0.00075,0.039,0.053,0.062,0.022,0.047,0.048,0.056,6.9e-06,5.6e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12490000,0.98,-0.008,-0.012,0.18,0.0094,-0.0062,0.017,0,0,-4.9e+02,-0.00093,-0.0058,-0.00013,-0.002,-0.00096,-0.14,0.2,-2.1e-06,0.43,5.3e-05,1.9e-06,-0.00031,0,0,-4.9e+02,0.00085,0.00075,0.039,0.06,0.071,0.021,0.053,0.055,0.056,6.8e-06,5.4e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12590000,0.98,-0.0081,-0.012,0.18,0.011,-0.01,0.018,0,0,-4.9e+02,-0.00092,-0.0058,-0.00013,-0.0021,-0.00083,-0.14,0.2,-1.9e-06,0.43,6.6e-05,2e-06,-0.00032,0,0,-4.9e+02,0.00077,0.0007,0.039,0.051,0.059,0.019,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12690000,0.98,-0.0081,-0.012,0.18,0.012,-0.014,0.018,0,0,-4.9e+02,-0.00091,-0.0058,-0.00013,-0.0023,-0.00078,-0.14,0.2,-1.9e-06,0.43,7.5e-05,5.9e-06,-0.00033,0,0,-4.9e+02,0.00077,0.00069,0.039,0.057,0.067,0.018,0.053,0.055,0.054,5.7e-06,4.6e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12790000,0.98,-0.0081,-0.012,0.18,0.014,-0.012,0.02,0,0,-4.9e+02,-0.00093,-0.0058,-0.00013,-0.0016,-0.0012,-0.14,0.2,-2e-06,0.43,3.9e-05,3e-05,-0.0003,0,0,-4.9e+02,0.0007,0.00065,0.039,0.049,0.056,0.016,0.046,0.047,0.052,4.8e-06,4.1e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12890000,0.98,-0.0081,-0.012,0.18,0.015,-0.013,0.021,0,0,-4.9e+02,-0.00094,-0.0058,-0.00013,-0.0012,-0.0014,-0.14,0.2,-2e-06,0.43,1.9e-05,3.4e-05,-0.00029,0,0,-4.9e+02,0.00071,0.00065,0.039,0.055,0.063,0.016,0.052,0.054,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +12990000,0.98,-0.0079,-0.012,0.18,0.013,-0.0088,0.021,0,0,-4.9e+02,-0.00098,-0.0058,-0.00012,-0.0011,-0.0015,-0.14,0.2,-2.5e-06,0.43,3.2e-05,9.2e-06,-0.00031,0,0,-4.9e+02,0.00065,0.00061,0.038,0.047,0.053,0.014,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13090000,0.98,-0.0079,-0.012,0.18,0.015,-0.0077,0.018,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.00055,-0.0017,-0.14,0.2,-2.6e-06,0.43,8.6e-06,1.4e-05,-0.0003,0,0,-4.9e+02,0.00065,0.00061,0.038,0.052,0.059,0.014,0.052,0.054,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13190000,0.98,-0.0079,-0.012,0.18,0.0096,-0.0078,0.017,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00031,-0.0022,-0.14,0.2,-2.7e-06,0.43,3.1e-05,1.2e-05,-0.00031,0,0,-4.9e+02,0.00061,0.00058,0.038,0.044,0.05,0.013,0.046,0.047,0.048,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13290000,0.98,-0.008,-0.012,0.18,0.011,-0.0095,0.015,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.00051,-0.0027,-0.14,0.2,-2.6e-06,0.43,3.9e-05,3.2e-05,-0.0003,0,0,-4.9e+02,0.00061,0.00058,0.038,0.049,0.056,0.013,0.052,0.054,0.048,3.6e-06,3e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13390000,0.98,-0.0079,-0.012,0.18,0.009,-0.0082,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0012,-0.0027,-0.14,0.2,-2.8e-06,0.43,7.7e-05,3e-05,-0.00034,0,0,-4.9e+02,0.00057,0.00056,0.038,0.042,0.047,0.012,0.045,0.046,0.047,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13490000,0.98,-0.0079,-0.012,0.18,0.011,-0.0069,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0012,-0.0032,-0.14,0.2,-2.8e-06,0.43,7.9e-05,5.3e-05,-0.00035,0,0,-4.9e+02,0.00058,0.00056,0.038,0.047,0.052,0.011,0.052,0.053,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13590000,0.98,-0.0079,-0.012,0.18,0.014,-0.0071,0.015,0,0,-4.9e+02,-0.00099,-0.0058,-0.00012,-0.0017,-0.0033,-0.14,0.2,-2.7e-06,0.43,8.6e-05,4.5e-05,-0.00034,0,0,-4.9e+02,0.00054,0.00053,0.038,0.04,0.044,0.011,0.045,0.046,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13690000,0.98,-0.0078,-0.012,0.18,0.014,-0.0083,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0013,-0.003,-0.14,0.2,-2.7e-06,0.43,7.3e-05,2.4e-05,-0.00032,0,0,-4.9e+02,0.00055,0.00053,0.038,0.044,0.049,0.011,0.052,0.053,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13790000,0.98,-0.0078,-0.012,0.18,0.019,-0.0045,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0018,-0.0024,-0.14,0.2,-3e-06,0.43,7.1e-05,2.9e-06,-0.00033,0,0,-4.9e+02,0.00052,0.00051,0.038,0.038,0.042,0.01,0.045,0.046,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13890000,0.98,-0.0076,-0.012,0.18,0.019,-0.0031,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0012,-0.0019,-0.14,0.2,-3.2e-06,0.43,4.9e-05,-1.2e-05,-0.00033,0,0,-4.9e+02,0.00052,0.00052,0.038,0.042,0.046,0.01,0.051,0.053,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13990000,0.98,-0.0076,-0.012,0.18,0.019,-0.0012,0.014,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.00062,-0.0024,-0.14,0.2,-3.1e-06,0.43,5.6e-05,-1.5e-05,-0.0003,0,0,-4.9e+02,0.0005,0.0005,0.038,0.036,0.039,0.0097,0.045,0.046,0.043,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +14090000,0.98,-0.0077,-0.011,0.18,0.017,-0.0084,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0024,-0.0022,-0.14,0.2,-3e-06,0.43,0.00011,-6.9e-06,-0.00034,0,0,-4.9e+02,0.0005,0.0005,0.038,0.04,0.043,0.0096,0.051,0.053,0.042,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14190000,0.98,-0.0078,-0.011,0.18,0.016,-0.0078,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0035,-0.0033,-0.14,0.2,-2.8e-06,0.43,0.00016,1.8e-05,-0.00036,0,0,-4.9e+02,0.00048,0.00048,0.038,0.034,0.037,0.0094,0.045,0.046,0.042,2.1e-06,1.9e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14290000,0.98,-0.0078,-0.011,0.18,0.018,-0.0084,0.013,0,0,-4.9e+02,-0.00099,-0.0058,-0.00014,-0.0036,-0.0035,-0.14,0.2,-2.7e-06,0.43,0.00017,2.1e-05,-0.00036,0,0,-4.9e+02,0.00048,0.00049,0.038,0.038,0.041,0.0092,0.051,0.052,0.041,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14390000,0.98,-0.0078,-0.011,0.18,0.018,-0.0098,0.015,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0033,-0.0043,-0.14,0.2,-2.6e-06,0.43,0.00017,2.6e-05,-0.00034,0,0,-4.9e+02,0.00047,0.00047,0.038,0.033,0.035,0.009,0.045,0.046,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14490000,0.98,-0.008,-0.011,0.18,0.018,-0.011,0.018,0,0,-4.9e+02,-0.00098,-0.0058,-0.00014,-0.0044,-0.0044,-0.14,0.2,-2.5e-06,0.43,0.0002,3.4e-05,-0.00036,0,0,-4.9e+02,0.00047,0.00047,0.038,0.036,0.038,0.009,0.051,0.052,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14590000,0.98,-0.0081,-0.011,0.18,0.017,-0.011,0.016,0,0,-4.9e+02,-0.00098,-0.0058,-0.00014,-0.0049,-0.0057,-0.14,0.2,-2.4e-06,0.43,0.00025,5.2e-05,-0.00037,0,0,-4.9e+02,0.00046,0.00046,0.038,0.031,0.033,0.0088,0.045,0.045,0.04,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14690000,0.98,-0.0082,-0.011,0.18,0.017,-0.011,0.016,0,0,-4.9e+02,-0.00098,-0.0058,-0.00014,-0.0048,-0.0061,-0.14,0.2,-2.3e-06,0.43,0.00025,5.9e-05,-0.00036,0,0,-4.9e+02,0.00046,0.00046,0.038,0.034,0.036,0.0088,0.05,0.051,0.039,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14790000,0.98,-0.0082,-0.011,0.18,0.019,-0.0038,0.016,0,0,-4.9e+02,-0.001,-0.0058,-0.00014,-0.0041,-0.0075,-0.14,0.2,-2.4e-06,0.43,0.00025,5.7e-05,-0.00034,0,0,-4.9e+02,0.00044,0.00045,0.038,0.03,0.031,0.0086,0.044,0.045,0.039,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14890000,0.98,-0.0082,-0.011,0.18,0.021,-0.006,0.02,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0036,-0.0091,-0.14,0.2,-2e-06,0.43,0.00025,7.8e-05,-0.0003,0,0,-4.9e+02,0.00045,0.00045,0.038,0.032,0.034,0.0087,0.05,0.051,0.039,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +14990000,0.98,-0.0084,-0.011,0.18,0.02,-0.0062,0.022,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0035,-0.011,-0.14,0.2,-1.8e-06,0.43,0.00027,0.00011,-0.00028,0,0,-4.9e+02,0.00044,0.00045,0.038,0.028,0.03,0.0085,0.044,0.045,0.038,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15090000,0.98,-0.0083,-0.011,0.18,0.021,-0.0055,0.026,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0036,-0.011,-0.14,0.2,-1.8e-06,0.43,0.00028,0.00011,-0.00028,0,0,-4.9e+02,0.00044,0.00045,0.038,0.031,0.032,0.0085,0.05,0.051,0.038,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15190000,0.98,-0.0085,-0.011,0.18,0.019,-0.0064,0.027,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0041,-0.012,-0.14,0.2,-1.6e-06,0.43,0.00031,0.00012,-0.00028,0,0,-4.9e+02,0.00043,0.00044,0.038,0.027,0.028,0.0085,0.044,0.045,0.038,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15290000,0.98,-0.0087,-0.012,0.18,0.022,-0.0071,0.026,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0035,-0.013,-0.14,0.2,-1.5e-06,0.43,0.00031,0.00015,-0.00026,0,0,-4.9e+02,0.00043,0.00044,0.038,0.029,0.031,0.0085,0.049,0.05,0.037,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15390000,0.98,-0.0088,-0.012,0.18,0.021,-0.0046,0.025,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0038,-0.014,-0.14,0.2,-1.6e-06,0.43,0.00034,0.00017,-0.00028,0,0,-4.9e+02,0.00042,0.00043,0.038,0.026,0.027,0.0084,0.044,0.044,0.037,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15490000,0.98,-0.0088,-0.012,0.18,0.022,-0.0074,0.025,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0038,-0.014,-0.14,0.2,-1.6e-06,0.43,0.00034,0.00017,-0.00028,0,0,-4.9e+02,0.00042,0.00043,0.038,0.028,0.029,0.0085,0.049,0.05,0.037,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15590000,0.98,-0.0089,-0.011,0.18,0.023,-0.0088,0.024,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0034,-0.014,-0.14,0.2,-1.6e-06,0.43,0.00034,0.00017,-0.00027,0,0,-4.9e+02,0.00041,0.00043,0.038,0.024,0.026,0.0084,0.043,0.044,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15690000,0.98,-0.0087,-0.011,0.18,0.024,-0.011,0.025,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0023,-0.012,-0.14,0.2,-2e-06,0.43,0.00029,0.00011,-0.00025,0,0,-4.9e+02,0.00041,0.00043,0.038,0.026,0.028,0.0085,0.049,0.049,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15790000,0.98,-0.0086,-0.011,0.18,0.019,-0.01,0.025,0,0,-4.9e+02,-0.001,-0.0058,-0.00011,-0.0012,-0.011,-0.14,0.2,-2.4e-06,0.43,0.00027,0.0001,-0.00024,0,0,-4.9e+02,0.00041,0.00042,0.038,0.023,0.025,0.0084,0.043,0.044,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15890000,0.98,-0.0088,-0.011,0.18,0.02,-0.0093,0.025,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0022,-0.012,-0.14,0.2,-2.2e-06,0.43,0.00031,0.00013,-0.00026,0,0,-4.9e+02,0.00041,0.00042,0.038,0.025,0.027,0.0085,0.048,0.049,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15990000,0.98,-0.0087,-0.011,0.18,0.018,-0.0083,0.022,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0025,-0.013,-0.14,0.2,-2.4e-06,0.43,0.00035,0.00017,-0.00028,0,0,-4.9e+02,0.0004,0.00042,0.038,0.022,0.024,0.0084,0.043,0.043,0.036,1.2e-06,1.1e-06,2.1e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +16090000,0.98,-0.0087,-0.011,0.18,0.019,-0.01,0.02,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0031,-0.014,-0.14,0.2,-2.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,-4.9e+02,0.0004,0.00042,0.038,0.024,0.025,0.0085,0.048,0.049,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16190000,0.98,-0.0087,-0.011,0.18,0.015,-0.0085,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0037,-0.015,-0.13,0.2,-2.3e-06,0.43,0.00041,0.00019,-0.00031,0,0,-4.9e+02,0.0004,0.00041,0.038,0.021,0.023,0.0084,0.043,0.043,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16290000,0.98,-0.0087,-0.011,0.18,0.017,-0.01,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00013,-0.0034,-0.014,-0.13,0.2,-2.3e-06,0.43,0.0004,0.00018,-0.0003,0,0,-4.9e+02,0.0004,0.00041,0.038,0.023,0.024,0.0085,0.047,0.048,0.036,1.2e-06,1e-06,2e-06,0.035,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16390000,0.98,-0.0088,-0.011,0.18,0.019,-0.009,0.018,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0029,-0.017,-0.13,0.2,-2.1e-06,0.43,0.00041,0.00022,-0.00028,0,0,-4.9e+02,0.00039,0.00041,0.038,0.021,0.022,0.0084,0.042,0.043,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16490000,0.98,-0.0089,-0.011,0.18,0.022,-0.011,0.021,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0033,-0.017,-0.13,0.2,-1.9e-06,0.43,0.00042,0.00023,-0.00028,0,0,-4.9e+02,0.00039,0.00041,0.038,0.022,0.023,0.0085,0.047,0.048,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16590000,0.98,-0.0089,-0.011,0.18,0.026,-0.011,0.024,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0031,-0.017,-0.13,0.2,-2.1e-06,0.43,0.00044,0.00023,-0.00029,0,0,-4.9e+02,0.00039,0.00041,0.038,0.02,0.021,0.0084,0.042,0.043,0.036,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16690000,0.98,-0.0089,-0.011,0.18,0.028,-0.016,0.024,0,0,-4.9e+02,-0.001,-0.0058,-0.00012,-0.0025,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00042,0.00022,-0.00028,0,0,-4.9e+02,0.00039,0.00041,0.038,0.021,0.023,0.0085,0.047,0.047,0.036,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16790000,0.98,-0.0088,-0.011,0.18,0.028,-0.015,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.002,-0.017,-0.13,0.2,-2.6e-06,0.43,0.00042,0.00022,-0.00028,0,0,-4.9e+02,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.042,0.042,0.036,1e-06,9.3e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16890000,0.98,-0.0087,-0.011,0.18,0.028,-0.015,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,-0.00087,-0.016,-0.13,0.2,-2.7e-06,0.43,0.00039,0.00021,-0.00026,0,0,-4.9e+02,0.00038,0.0004,0.038,0.02,0.022,0.0085,0.046,0.047,0.036,1e-06,9.2e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +16990000,0.98,-0.0088,-0.011,0.18,0.026,-0.015,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,-0.00051,-0.017,-0.13,0.2,-2.7e-06,0.43,0.0004,0.00023,-0.00026,0,0,-4.9e+02,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,1e-06,9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17090000,0.98,-0.009,-0.011,0.18,0.03,-0.018,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,-0.0009,-0.019,-0.13,0.2,-2.8e-06,0.43,0.00044,0.0003,-0.00027,0,0,-4.9e+02,0.00038,0.0004,0.038,0.02,0.021,0.0085,0.046,0.047,0.035,9.9e-07,8.9e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17190000,0.98,-0.0091,-0.011,0.18,0.028,-0.023,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0018,-0.019,-0.13,0.2,-3.3e-06,0.43,0.00048,0.00031,-0.00031,0,0,-4.9e+02,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,9.6e-07,8.7e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17290000,0.98,-0.0091,-0.011,0.18,0.031,-0.024,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0025,-0.019,-0.13,0.2,-3.3e-06,0.43,0.0005,0.00032,-0.00033,0,0,-4.9e+02,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.045,0.046,0.036,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17390000,0.98,-0.009,-0.011,0.18,0.025,-0.025,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0011,-0.018,-0.13,0.2,-3.6e-06,0.43,0.00048,0.00032,-0.00032,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.041,0.041,0.035,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17490000,0.98,-0.009,-0.011,0.18,0.024,-0.026,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.0014,-0.018,-0.13,0.2,-3.6e-06,0.43,0.00049,0.00032,-0.00032,0,0,-4.9e+02,0.00037,0.00039,0.038,0.018,0.02,0.0085,0.045,0.046,0.036,9.3e-07,8.3e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17590000,0.98,-0.009,-0.011,0.18,0.021,-0.023,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00091,-0.019,-0.13,0.2,-4.2e-06,0.43,0.0005,0.00032,-0.00033,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.04,0.041,0.035,9e-07,8.1e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17690000,0.98,-0.0091,-0.011,0.18,0.022,-0.024,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,-0.00059,-0.019,-0.13,0.2,-4e-06,0.43,0.00048,0.0003,-0.00031,0,0,-4.9e+02,0.00037,0.00039,0.038,0.018,0.019,0.0084,0.045,0.045,0.035,9e-07,8e-07,2e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17790000,0.98,-0.0091,-0.011,0.18,0.023,-0.023,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,0.00019,-0.019,-0.13,0.2,-3.9e-06,0.43,0.00046,0.00027,-0.00029,0,0,-4.9e+02,0.00037,0.00039,0.038,0.016,0.017,0.0084,0.04,0.041,0.036,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17890000,0.98,-0.009,-0.011,0.18,0.026,-0.025,0.025,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,0.0008,-0.018,-0.13,0.2,-3.9e-06,0.43,0.00043,0.00025,-0.00027,0,0,-4.9e+02,0.00037,0.00039,0.038,0.017,0.019,0.0084,0.044,0.045,0.036,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17990000,0.98,-0.009,-0.011,0.18,0.025,-0.021,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,0.0016,-0.02,-0.13,0.2,-4e-06,0.43,0.00043,0.00025,-0.00026,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0083,0.04,0.041,0.035,8.5e-07,7.6e-07,2e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +18090000,0.98,-0.0091,-0.011,0.18,0.026,-0.023,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00012,0.0017,-0.02,-0.13,0.2,-3.8e-06,0.43,0.00042,0.00024,-0.00025,0,0,-4.9e+02,0.00036,0.00038,0.038,0.017,0.018,0.0083,0.044,0.045,0.036,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18190000,0.98,-0.0091,-0.011,0.18,0.025,-0.021,0.024,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,0.0033,-0.021,-0.13,0.2,-4.1e-06,0.43,0.0004,0.00027,-0.00023,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0082,0.04,0.04,0.035,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18290000,0.98,-0.0092,-0.011,0.18,0.028,-0.022,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.0001,0.0035,-0.022,-0.13,0.2,-3.8e-06,0.43,0.0004,0.00028,-0.00022,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.018,0.0082,0.044,0.044,0.036,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18390000,0.98,-0.0091,-0.011,0.18,0.027,-0.02,0.023,0,0,-4.9e+02,-0.0011,-0.0058,-0.00011,0.0038,-0.022,-0.13,0.2,-4.2e-06,0.43,0.00041,0.00029,-0.00023,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18490000,0.98,-0.0092,-0.011,0.18,0.031,-0.021,0.022,0,0,-4.9e+02,-0.0011,-0.0058,-0.0001,0.0044,-0.022,-0.13,0.2,-4.1e-06,0.43,0.00039,0.00029,-0.00021,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0082,0.043,0.044,0.036,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18590000,0.98,-0.0089,-0.011,0.18,0.028,-0.02,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0047,-0.021,-0.13,0.2,-4.6e-06,0.43,0.00039,0.00026,-0.00022,0,0,-4.9e+02,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18690000,0.98,-0.0088,-0.011,0.18,0.028,-0.019,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-9.7e-05,0.0057,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00035,0.00023,-0.0002,0,0,-4.9e+02,0.00036,0.00038,0.038,0.016,0.017,0.0081,0.043,0.044,0.035,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18790000,0.98,-0.0088,-0.011,0.18,0.026,-0.019,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-9.8e-05,0.0062,-0.02,-0.13,0.2,-5.1e-06,0.43,0.00035,0.00024,-0.00021,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.008,0.039,0.04,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18890000,0.98,-0.0088,-0.011,0.18,0.027,-0.019,0.018,0,0,-4.9e+02,-0.0012,-0.0058,-9.9e-05,0.006,-0.02,-0.13,0.2,-5.2e-06,0.43,0.00037,0.00026,-0.00021,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.044,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +18990000,0.98,-0.0087,-0.011,0.18,0.024,-0.019,0.019,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.0068,-0.019,-0.13,0.2,-5.8e-06,0.43,0.00036,0.00025,-0.00022,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.035,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19090000,0.98,-0.0088,-0.011,0.18,0.023,-0.02,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-9.3e-05,0.0074,-0.019,-0.13,0.2,-5.7e-06,0.43,0.00035,0.00025,-0.00021,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.008,0.042,0.043,0.036,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19190000,0.98,-0.0087,-0.011,0.18,0.02,-0.02,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.0073,-0.019,-0.13,0.2,-6.5e-06,0.43,0.00037,0.00026,-0.00023,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19290000,0.98,-0.0087,-0.011,0.18,0.021,-0.02,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.0073,-0.019,-0.13,0.2,-6.5e-06,0.43,0.00037,0.00027,-0.00024,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.017,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0079,-0.019,-0.13,0.2,-6.9e-06,0.43,0.00036,0.00026,-0.00023,0,0,-4.9e+02,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,6.9e-07,6.2e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19490000,0.98,-0.0089,-0.011,0.18,0.021,-0.019,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0073,-0.02,-0.13,0.2,-6.5e-06,0.43,0.00037,0.00024,-0.00023,0,0,-4.9e+02,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,6.9e-07,6.1e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19590000,0.98,-0.0088,-0.011,0.18,0.018,-0.02,0.023,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0076,-0.02,-0.13,0.2,-6.8e-06,0.43,0.00037,0.00024,-0.00023,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.015,0.0076,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19690000,0.98,-0.0088,-0.011,0.18,0.018,-0.019,0.022,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.0081,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00036,0.00024,-0.00022,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.016,0.0076,0.042,0.043,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19790000,0.98,-0.0089,-0.011,0.18,0.016,-0.017,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0082,-0.021,-0.13,0.2,-7e-06,0.43,0.00036,0.00025,-0.00023,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19890000,0.98,-0.0089,-0.011,0.18,0.017,-0.018,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0082,-0.021,-0.13,0.2,-7e-06,0.43,0.00036,0.00025,-0.00023,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19990000,0.98,-0.0089,-0.012,0.18,0.015,-0.018,0.018,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0092,-0.021,-0.13,0.2,-7.5e-06,0.43,0.00035,0.00025,-0.00023,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.038,0.038,0.035,6.4e-07,5.7e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.021,0.019,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.0093,-0.021,-0.13,0.2,-7.5e-06,0.43,0.00035,0.00026,-0.00023,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.4e-07,5.6e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5.1 +20190000,0.98,-0.009,-0.012,0.18,0.017,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0094,-0.022,-0.13,0.2,-8e-06,0.43,0.00035,0.00027,-0.00025,0,0,-4.9e+02,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20290000,0.98,-0.009,-0.012,0.18,0.015,-0.02,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00012,0.0094,-0.022,-0.13,0.2,-8e-06,0.43,0.00036,0.00028,-0.00025,0,0,-4.9e+02,0.00034,0.00036,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20390000,0.98,-0.0089,-0.012,0.18,0.013,-0.017,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.01,-0.022,-0.13,0.2,-8.2e-06,0.43,0.00034,0.00026,-0.00024,0,0,-4.9e+02,0.00034,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20490000,0.98,-0.0089,-0.012,0.18,0.0096,-0.019,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.011,-0.022,-0.13,0.2,-8e-06,0.43,0.00034,0.00025,-0.00023,0,0,-4.9e+02,0.00034,0.00035,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20590000,0.98,-0.0089,-0.012,0.18,0.0088,-0.018,0.02,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.012,-0.022,-0.13,0.2,-7.9e-06,0.43,0.00032,0.00023,-0.00022,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20690000,0.98,-0.0088,-0.012,0.18,0.0078,-0.018,0.021,0,0,-4.9e+02,-0.0012,-0.0058,-0.00011,0.012,-0.022,-0.13,0.2,-8.1e-06,0.43,0.00032,0.00023,-0.00022,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.015,0.0072,0.041,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20790000,0.98,-0.0082,-0.012,0.18,0.0039,-0.015,0.006,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.012,-0.022,-0.13,0.2,-8.5e-06,0.43,0.0003,0.00023,-0.00022,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.8e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20890000,0.98,0.00095,-0.0079,0.18,1.9e-05,-0.0038,-0.11,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.013,-0.023,-0.13,0.2,-9.4e-06,0.43,0.0003,0.00035,-0.00017,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.015,0.0071,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20990000,0.98,0.0043,-0.0044,0.18,-0.012,0.015,-0.25,0,0,-4.9e+02,-0.0012,-0.0058,-0.0001,0.013,-0.023,-0.13,0.2,-9.4e-06,0.43,0.0003,0.00034,-0.00013,0,0,-4.9e+02,0.00033,0.00035,0.038,0.013,0.014,0.007,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21090000,0.98,0.0027,-0.0048,0.18,-0.023,0.031,-0.37,0,0,-4.9e+02,-0.0012,-0.0058,-9.9e-05,0.013,-0.023,-0.13,0.2,-7.6e-06,0.43,0.00035,0.00014,-0.00018,0,0,-4.9e+02,0.00033,0.00035,0.038,0.014,0.015,0.007,0.04,0.041,0.035,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21190000,0.98,-9.1e-05,-0.0064,0.18,-0.029,0.037,-0.5,0,0,-4.9e+02,-0.0012,-0.0058,-9.1e-05,0.013,-0.024,-0.13,0.2,-7e-06,0.43,0.00036,0.00016,-0.00016,0,0,-4.9e+02,0.00033,0.00034,0.038,0.013,0.014,0.0069,0.037,0.038,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21290000,0.98,-0.0023,-0.0077,0.18,-0.028,0.039,-0.63,0,0,-4.9e+02,-0.0012,-0.0058,-9.9e-05,0.012,-0.024,-0.13,0.2,-7.7e-06,0.43,0.00034,0.0002,-9.5e-05,0,0,-4.9e+02,0.00033,0.00034,0.037,0.014,0.015,0.0069,0.04,0.041,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21390000,0.98,-0.0037,-0.0083,0.18,-0.026,0.036,-0.75,0,0,-4.9e+02,-0.0012,-0.0058,-9.7e-05,0.012,-0.024,-0.13,0.2,-7.2e-06,0.43,0.00036,0.00013,-0.00011,0,0,-4.9e+02,0.00032,0.00034,0.037,0.013,0.014,0.0068,0.037,0.038,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21490000,0.98,-0.0045,-0.0088,0.18,-0.021,0.033,-0.89,0,0,-4.9e+02,-0.0012,-0.0058,-9.1e-05,0.013,-0.024,-0.13,0.2,-7.2e-06,0.43,0.00035,0.00015,-0.00016,0,0,-4.9e+02,0.00032,0.00034,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21590000,0.98,-0.0049,-0.0088,0.18,-0.014,0.03,-1,0,0,-4.9e+02,-0.0012,-0.0058,-8.5e-05,0.013,-0.024,-0.13,0.2,-7.3e-06,0.43,0.00034,0.00021,-0.00017,0,0,-4.9e+02,0.00032,0.00034,0.037,0.013,0.015,0.0067,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21690000,0.98,-0.0052,-0.0086,0.18,-0.011,0.025,-1.1,0,0,-4.9e+02,-0.0012,-0.0058,-7.8e-05,0.014,-0.024,-0.13,0.2,-7.2e-06,0.43,0.00031,0.00025,-0.00016,0,0,-4.9e+02,0.00032,0.00034,0.037,0.014,0.016,0.0067,0.04,0.041,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21790000,0.98,-0.0055,-0.0088,0.18,-0.0062,0.021,-1.3,0,0,-4.9e+02,-0.0013,-0.0058,-6.9e-05,0.015,-0.023,-0.13,0.2,-7.2e-06,0.43,0.00031,0.00024,-0.00021,0,0,-4.9e+02,0.00032,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21890000,0.98,-0.0058,-0.0089,0.18,-0.0025,0.016,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-7.1e-05,0.015,-0.023,-0.13,0.2,-7.6e-06,0.43,0.00028,0.00026,-0.0002,0,0,-4.9e+02,0.00032,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21990000,0.98,-0.0064,-0.0092,0.18,-0.00048,0.011,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-6.6e-05,0.015,-0.022,-0.13,0.2,-7.3e-06,0.43,0.00031,0.00027,-0.00022,0,0,-4.9e+02,0.00031,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22090000,0.98,-0.0071,-0.01,0.18,0.0015,0.0077,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.7e-05,0.015,-0.022,-0.13,0.2,-7.2e-06,0.43,0.00031,0.00029,-0.00023,0,0,-4.9e+02,0.00031,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22190000,0.98,-0.0075,-0.01,0.18,0.0073,0.0034,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.9e-05,0.016,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00031,0.00031,-0.00023,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.014,0.0065,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22290000,0.98,-0.0082,-0.01,0.18,0.013,-0.0024,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.1e-05,0.016,-0.021,-0.13,0.2,-7.3e-06,0.43,0.00031,0.0003,-0.00022,0,0,-4.9e+02,0.00031,0.00032,0.037,0.014,0.015,0.0065,0.04,0.041,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22390000,0.98,-0.0085,-0.011,0.18,0.017,-0.011,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.3e-05,0.015,-0.02,-0.13,0.2,-7.4e-06,0.43,0.00032,0.00031,-0.00024,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.014,0.0064,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22490000,0.98,-0.0087,-0.011,0.18,0.022,-0.018,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.7e-05,0.014,-0.02,-0.13,0.2,-7.8e-06,0.43,0.00033,0.00033,-0.00026,0,0,-4.9e+02,0.00031,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22590000,0.98,-0.0086,-0.012,0.18,0.029,-0.025,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.9e-05,0.015,-0.02,-0.13,0.2,-7.3e-06,0.43,0.00033,0.00034,-0.00025,0,0,-4.9e+02,0.0003,0.00032,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.03,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.1e-05,0.015,-0.021,-0.13,0.2,-7.3e-06,0.43,0.00033,0.00035,-0.00027,0,0,-4.9e+02,0.0003,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.038,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.5e-05,0.014,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00031,0.00031,-0.00029,0,0,-4.9e+02,0.0003,0.00031,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22890000,0.98,-0.0087,-0.013,0.18,0.042,-0.043,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.6e-05,0.015,-0.021,-0.13,0.2,-7.1e-06,0.43,0.00032,0.00032,-0.00028,0,0,-4.9e+02,0.0003,0.00031,0.037,0.013,0.015,0.0063,0.04,0.041,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.047,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-3.8e-05,0.015,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00032,0.0003,-0.00025,0,0,-4.9e+02,0.0003,0.00031,0.037,0.012,0.014,0.0062,0.036,0.038,0.033,4.3e-07,3.9e-07,1.6e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23090000,0.98,-0.0086,-0.013,0.18,0.051,-0.052,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-3.6e-05,0.015,-0.02,-0.13,0.2,-7.5e-06,0.43,0.0003,0.0003,-0.00023,0,0,-4.9e+02,0.0003,0.00031,0.037,0.013,0.014,0.0062,0.04,0.041,0.033,4.3e-07,3.9e-07,1.5e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23190000,0.98,-0.0086,-0.014,0.18,0.057,-0.053,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4e-05,0.015,-0.019,-0.13,0.2,-8.3e-06,0.43,0.00028,0.00028,-0.00023,0,0,-4.9e+02,0.00029,0.00031,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23290000,0.98,-0.0091,-0.014,0.18,0.062,-0.059,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.015,-0.02,-0.13,0.2,-8.3e-06,0.43,0.00025,0.00032,-0.00023,0,0,-4.9e+02,0.00029,0.00031,0.037,0.013,0.014,0.0062,0.039,0.041,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23390000,0.98,-0.009,-0.014,0.18,0.067,-0.062,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-5.1e-05,0.016,-0.019,-0.13,0.2,-8.5e-06,0.43,0.00026,0.00029,-0.00022,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23490000,0.98,-0.0091,-0.014,0.18,0.072,-0.064,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-4.3e-05,0.016,-0.02,-0.13,0.2,-8.3e-06,0.43,0.00024,0.00035,-0.00026,0,0,-4.9e+02,0.00029,0.0003,0.037,0.013,0.014,0.0061,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23590000,0.98,-0.0093,-0.014,0.18,0.075,-0.066,-1.4,0,0,-4.9e+02,-0.0013,-0.0058,-3.9e-05,0.016,-0.019,-0.13,0.2,-9.2e-06,0.43,0.0002,0.00032,-0.00022,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.006,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23690000,0.98,-0.01,-0.015,0.18,0.074,-0.068,-1.3,0,0,-4.9e+02,-0.0013,-0.0058,-3.1e-05,0.016,-0.019,-0.13,0.2,-9e-06,0.43,0.00018,0.00034,-0.00022,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.014,0.006,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23790000,0.98,-0.012,-0.018,0.18,0.068,-0.064,-0.95,0,0,-4.9e+02,-0.0013,-0.0058,-2.9e-05,0.018,-0.019,-0.13,0.2,-8.6e-06,0.43,0.00016,0.00038,-0.0002,0,0,-4.9e+02,0.00029,0.0003,0.037,0.011,0.013,0.006,0.036,0.037,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23890000,0.98,-0.015,-0.022,0.18,0.064,-0.064,-0.52,0,0,-4.9e+02,-0.0013,-0.0058,-2.7e-05,0.018,-0.02,-0.13,0.2,-8.7e-06,0.43,0.00015,0.0004,-0.00023,0,0,-4.9e+02,0.00029,0.0003,0.037,0.012,0.013,0.006,0.039,0.041,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23990000,0.98,-0.017,-0.024,0.18,0.063,-0.063,-0.13,0,0,-4.9e+02,-0.0013,-0.0058,-3.4e-05,0.019,-0.019,-0.13,0.2,-8.7e-06,0.43,0.00011,0.00042,2.4e-05,0,0,-4.9e+02,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.033,3.9e-07,3.5e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24090000,0.98,-0.017,-0.023,0.18,0.07,-0.071,0.099,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.019,-0.019,-0.13,0.2,-8.7e-06,0.43,0.00013,0.00039,2.6e-05,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24190000,0.98,-0.014,-0.019,0.18,0.08,-0.076,0.089,0,0,-4.9e+02,-0.0013,-0.0058,-3.7e-05,0.02,-0.019,-0.13,0.2,-8.3e-06,0.43,0.00012,0.00036,0.00013,0,0,-4.9e+02,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.032,3.8e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24290000,0.98,-0.012,-0.016,0.18,0.084,-0.08,0.067,0,0,-4.9e+02,-0.0013,-0.0058,-3.5e-05,0.02,-0.019,-0.13,0.2,-7.9e-06,0.43,0.00016,0.00031,0.00012,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24390000,0.98,-0.011,-0.015,0.18,0.077,-0.074,0.083,0,0,-4.9e+02,-0.0013,-0.0058,-3.4e-05,0.022,-0.02,-0.13,0.2,-6.5e-06,0.43,0.00015,0.00036,0.00019,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24490000,0.98,-0.011,-0.015,0.18,0.073,-0.071,0.081,0,0,-4.9e+02,-0.0013,-0.0058,-2e-05,0.023,-0.02,-0.13,0.2,-6.5e-06,0.43,7.6e-05,0.00047,0.00023,0,0,-4.9e+02,0.00028,0.0003,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24590000,0.98,-0.012,-0.015,0.18,0.069,-0.067,0.077,0,0,-4.9e+02,-0.0013,-0.0058,-3.2e-05,0.024,-0.021,-0.13,0.2,-5.2e-06,0.43,0.00012,0.00044,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24690000,0.98,-0.012,-0.015,0.18,0.067,-0.067,0.076,0,0,-4.9e+02,-0.0013,-0.0058,-3e-05,0.024,-0.021,-0.13,0.2,-5.4e-06,0.43,0.0001,0.00047,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24790000,0.98,-0.012,-0.015,0.18,0.064,-0.065,0.068,0,0,-4.9e+02,-0.0013,-0.0058,-3.8e-05,0.026,-0.022,-0.13,0.2,-4.8e-06,0.43,9.9e-05,0.00047,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24890000,0.98,-0.012,-0.014,0.18,0.063,-0.068,0.057,0,0,-4.9e+02,-0.0013,-0.0058,-3.3e-05,0.026,-0.022,-0.13,0.2,-4.6e-06,0.43,9.6e-05,0.00048,0.00026,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24990000,0.98,-0.012,-0.014,0.18,0.054,-0.065,0.05,0,0,-4.9e+02,-0.0014,-0.0058,-4.7e-05,0.027,-0.023,-0.13,0.2,-4.8e-06,0.43,6e-05,0.00059,0.00027,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25090000,0.98,-0.012,-0.014,0.18,0.051,-0.064,0.048,0,0,-4.9e+02,-0.0014,-0.0058,-4.7e-05,0.028,-0.023,-0.13,0.2,-5.4e-06,0.43,4.1e-05,0.00066,0.00031,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25190000,0.98,-0.012,-0.014,0.18,0.045,-0.058,0.048,0,0,-4.9e+02,-0.0014,-0.0058,-6.5e-05,0.029,-0.024,-0.13,0.2,-5.4e-06,0.43,1.9e-05,0.00069,0.0003,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25290000,0.98,-0.012,-0.013,0.18,0.041,-0.06,0.043,0,0,-4.9e+02,-0.0014,-0.0058,-7.2e-05,0.029,-0.024,-0.13,0.2,-6e-06,0.43,1e-05,0.00072,0.00027,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25390000,0.98,-0.012,-0.013,0.18,0.032,-0.054,0.041,0,0,-4.9e+02,-0.0014,-0.0058,-8.8e-05,0.031,-0.025,-0.13,0.2,-6.9e-06,0.43,-3e-05,0.00077,0.00029,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25490000,0.98,-0.013,-0.013,0.18,0.028,-0.054,0.041,0,0,-4.9e+02,-0.0014,-0.0058,-9e-05,0.031,-0.025,-0.13,0.2,-6.6e-06,0.43,-3.6e-05,0.00073,0.00026,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25590000,0.98,-0.013,-0.013,0.18,0.023,-0.05,0.042,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.032,-0.026,-0.13,0.2,-7.4e-06,0.43,-6.9e-05,0.00075,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25690000,0.98,-0.012,-0.012,0.18,0.023,-0.05,0.031,0,0,-4.9e+02,-0.0014,-0.0058,-0.0001,0.032,-0.026,-0.13,0.2,-7.5e-06,0.43,-6.4e-05,0.00078,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25790000,0.98,-0.012,-0.012,0.18,0.011,-0.041,0.031,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.033,-0.026,-0.13,0.2,-8e-06,0.43,-0.00012,0.00071,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25890000,0.98,-0.012,-0.012,0.18,0.0057,-0.04,0.033,0,0,-4.9e+02,-0.0014,-0.0058,-0.00013,0.033,-0.026,-0.13,0.2,-8.2e-06,0.43,-0.00014,0.00068,0.00019,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25990000,0.98,-0.012,-0.012,0.18,-0.0033,-0.033,0.027,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.035,-0.027,-0.13,0.2,-9.7e-06,0.43,-0.0002,0.00066,0.00017,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26090000,0.98,-0.012,-0.012,0.18,-0.0079,-0.033,0.025,0,0,-4.9e+02,-0.0014,-0.0058,-0.00013,0.035,-0.027,-0.13,0.2,-9.1e-06,0.43,-0.0002,0.00065,0.0002,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26190000,0.98,-0.012,-0.012,0.18,-0.015,-0.026,0.021,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.036,-0.027,-0.13,0.2,-9.5e-06,0.43,-0.00022,0.00064,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26290000,0.98,-0.012,-0.013,0.18,-0.015,-0.026,0.015,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.036,-0.027,-0.13,0.2,-1e-05,0.43,-0.00023,0.00066,0.00019,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26390000,0.98,-0.011,-0.013,0.18,-0.021,-0.018,0.019,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.037,-0.028,-0.13,0.2,-1.1e-05,0.43,-0.00027,0.00063,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26490000,0.98,-0.011,-0.013,0.18,-0.023,-0.016,0.028,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.037,-0.028,-0.13,0.2,-1.2e-05,0.43,-0.00028,0.00066,0.00016,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26590000,0.98,-0.01,-0.013,0.18,-0.026,-0.0074,0.029,0,0,-4.9e+02,-0.0015,-0.0058,-0.00017,0.038,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00031,0.00068,0.00015,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26690000,0.98,-0.01,-0.013,0.18,-0.027,-0.0035,0.027,0,0,-4.9e+02,-0.0014,-0.0058,-0.00018,0.037,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00033,0.00069,0.00015,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.00085,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.00018,0.038,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00035,0.00067,0.00014,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26890000,0.98,-0.0092,-0.012,0.18,-0.041,0.0037,0.022,0,0,-4.9e+02,-0.0015,-0.0058,-0.00018,0.038,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00035,0.00065,0.00014,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.011,0.021,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.039,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00037,0.00063,0.00015,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27090000,0.98,-0.0085,-0.013,0.18,-0.05,0.017,0.025,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.039,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00036,0.00063,0.00015,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27190000,0.98,-0.0086,-0.013,0.18,-0.056,0.024,0.027,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.039,-0.028,-0.13,0.2,-1.5e-05,0.43,-0.00037,0.00061,0.00015,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27290000,0.98,-0.0088,-0.014,0.18,-0.063,0.029,0.14,0,0,-4.9e+02,-0.0015,-0.0058,-0.00019,0.039,-0.028,-0.13,0.2,-1.5e-05,0.43,-0.00038,0.00062,0.00015,0,0,-4.9e+02,0.00028,0.00029,0.037,0.012,0.013,0.0054,0.038,0.039,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27390000,0.98,-0.01,-0.016,0.18,-0.071,0.037,0.46,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.039,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.00045,0.00054,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27490000,0.98,-0.012,-0.018,0.18,-0.075,0.042,0.78,0,0,-4.9e+02,-0.0015,-0.0058,-0.00021,0.039,-0.028,-0.13,0.2,-1.7e-05,0.43,-0.00042,0.0005,0.00021,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.013,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27590000,0.98,-0.011,-0.017,0.18,-0.07,0.045,0.87,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.039,-0.028,-0.13,0.2,-1.7e-05,0.43,-0.0004,0.00044,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27690000,0.98,-0.01,-0.014,0.18,-0.066,0.041,0.78,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.039,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00039,0.00043,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27790000,0.98,-0.0088,-0.013,0.18,-0.066,0.04,0.77,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.039,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00039,0.0004,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27890000,0.98,-0.0085,-0.013,0.18,-0.071,0.046,0.81,0,0,-4.9e+02,-0.0015,-0.0058,-0.0002,0.039,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00039,0.00039,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27990000,0.98,-0.0089,-0.013,0.18,-0.072,0.049,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-0.00019,0.038,-0.029,-0.12,0.2,-1.8e-05,0.43,-0.00039,0.00033,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28090000,0.98,-0.0092,-0.013,0.18,-0.076,0.049,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-0.00019,0.038,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.0004,0.00036,0.00024,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28190000,0.98,-0.0086,-0.013,0.18,-0.077,0.047,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00018,0.038,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00038,0.00034,0.00025,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28290000,0.98,-0.0081,-0.014,0.18,-0.081,0.05,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.038,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00039,0.00036,0.00022,0,0,-4.9e+02,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.038,-0.029,-0.12,0.2,-1.8e-05,0.43,-0.00044,0.00027,0.00023,0,0,-4.9e+02,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28490000,0.98,-0.0084,-0.015,0.18,-0.085,0.057,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00017,0.038,-0.029,-0.12,0.2,-1.8e-05,0.43,-0.0004,0.00025,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28590000,0.98,-0.0085,-0.015,0.18,-0.079,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00015,0.037,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00037,0.00023,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28690000,0.98,-0.0082,-0.014,0.18,-0.078,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00016,0.037,-0.029,-0.12,0.2,-1.8e-05,0.43,-0.00035,0.00024,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28790000,0.98,-0.0076,-0.014,0.18,-0.076,0.055,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00015,0.036,-0.029,-0.12,0.2,-1.9e-05,0.43,-0.00037,0.00013,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28890000,0.98,-0.0074,-0.014,0.18,-0.08,0.057,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00014,0.036,-0.029,-0.12,0.2,-1.9e-05,0.43,-0.00037,0.00017,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28990000,0.98,-0.0072,-0.014,0.18,-0.077,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00013,0.035,-0.029,-0.12,0.2,-2e-05,0.43,-0.00041,1.5e-05,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29090000,0.98,-0.007,-0.014,0.18,-0.08,0.056,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00013,0.035,-0.029,-0.12,0.2,-1.9e-05,0.43,-0.00043,-4e-06,0.00027,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29190000,0.98,-0.0069,-0.014,0.18,-0.078,0.056,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.034,-0.029,-0.12,0.2,-2.1e-05,0.43,-0.00046,-0.00014,0.00028,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29290000,0.98,-0.0072,-0.014,0.18,-0.081,0.062,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00012,0.034,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00045,-0.00016,0.00028,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29390000,0.98,-0.0076,-0.013,0.18,-0.077,0.061,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-0.00011,0.034,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00049,-0.00029,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.8e-07,2.6e-07,9.9e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29490000,0.98,-0.0076,-0.013,0.18,-0.08,0.062,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-9.9e-05,0.034,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00051,-0.00026,0.00027,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29590000,0.98,-0.0075,-0.013,0.18,-0.077,0.061,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-8.2e-05,0.033,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.00056,-0.00037,0.00027,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29690000,0.98,-0.0075,-0.013,0.18,-0.082,0.06,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-7.5e-05,0.033,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.00057,-0.00033,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29790000,0.98,-0.0073,-0.013,0.18,-0.079,0.054,0.81,0,0,-4.9e+02,-0.0014,-0.0058,-5.9e-05,0.032,-0.029,-0.12,0.2,-2.6e-05,0.43,-0.00063,-0.00045,0.00026,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29890000,0.98,-0.0068,-0.014,0.18,-0.08,0.055,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.3e-05,0.032,-0.028,-0.12,0.2,-2.6e-05,0.43,-0.00065,-0.00043,0.00023,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29990000,0.98,-0.007,-0.014,0.18,-0.075,0.051,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-4.2e-05,0.031,-0.029,-0.12,0.2,-2.7e-05,0.43,-0.00063,-0.00048,0.00025,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.5e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30090000,0.98,-0.0071,-0.014,0.18,-0.077,0.051,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.2e-05,0.031,-0.029,-0.12,0.2,-2.8e-05,0.43,-0.00058,-0.00055,0.0003,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.4e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30190000,0.98,-0.0071,-0.014,0.18,-0.071,0.047,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.4e-05,0.03,-0.029,-0.12,0.2,-3.1e-05,0.43,-0.00059,-0.00077,0.00036,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30290000,0.98,-0.0071,-0.014,0.18,-0.071,0.048,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-5.3e-05,0.03,-0.029,-0.12,0.2,-3e-05,0.43,-0.00063,-0.00082,0.00037,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30390000,0.98,-0.0071,-0.013,0.18,-0.065,0.043,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-3.5e-05,0.03,-0.03,-0.12,0.2,-3.1e-05,0.43,-0.00077,-0.001,0.00037,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30490000,0.98,-0.0071,-0.014,0.18,-0.068,0.043,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-2.9e-05,0.03,-0.03,-0.12,0.2,-3.1e-05,0.43,-0.00081,-0.001,0.00035,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30590000,0.98,-0.0074,-0.014,0.17,-0.064,0.041,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.4e-05,0.029,-0.03,-0.12,0.2,-3.2e-05,0.43,-0.00092,-0.0011,0.00035,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.1e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30690000,0.98,-0.0078,-0.014,0.18,-0.062,0.039,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-1.4e-05,0.029,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00089,-0.0011,0.00035,0,0,-4.9e+02,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.5e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30790000,0.98,-0.0075,-0.014,0.17,-0.056,0.034,0.8,0,0,-4.9e+02,-0.0014,-0.0058,-9.6e-06,0.029,-0.031,-0.12,0.2,-3.3e-05,0.43,-0.00097,-0.0013,0.00039,0,0,-4.9e+02,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30890000,0.98,-0.0069,-0.014,0.17,-0.056,0.03,0.79,0,0,-4.9e+02,-0.0014,-0.0058,-1.6e-05,0.029,-0.031,-0.12,0.2,-3.4e-05,0.43,-0.00087,-0.0012,0.00041,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30990000,0.98,-0.0071,-0.013,0.17,-0.048,0.025,0.8,0,0,-4.9e+02,-0.0013,-0.0057,-8.9e-06,0.028,-0.032,-0.12,0.2,-3.5e-05,0.43,-0.00091,-0.0013,0.00044,0,0,-4.9e+02,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31090000,0.98,-0.0073,-0.014,0.17,-0.048,0.024,0.79,0,0,-4.9e+02,-0.0013,-0.0057,-1.3e-05,0.028,-0.033,-0.12,0.2,-3.5e-05,0.43,-0.00086,-0.0013,0.00045,0,0,-4.9e+02,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31190000,0.98,-0.0075,-0.014,0.17,-0.043,0.02,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.6e-06,0.028,-0.033,-0.12,0.2,-3.6e-05,0.43,-0.00096,-0.0013,0.00045,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31290000,0.98,-0.0077,-0.014,0.17,-0.04,0.017,0.8,0,0,-4.9e+02,-0.0013,-0.0057,7.7e-06,0.029,-0.034,-0.12,0.2,-3.5e-05,0.43,-0.001,-0.0012,0.00043,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31390000,0.98,-0.0075,-0.013,0.17,-0.035,0.011,0.8,0,0,-4.9e+02,-0.0013,-0.0057,7.1e-06,0.028,-0.034,-0.12,0.2,-3.4e-05,0.43,-0.0011,-0.0016,0.00048,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31490000,0.98,-0.0073,-0.014,0.17,-0.036,0.0078,0.8,0,0,-4.9e+02,-0.0013,-0.0057,5.4e-06,0.028,-0.034,-0.12,0.2,-3.3e-05,0.43,-0.0011,-0.0018,0.0005,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31590000,0.98,-0.0071,-0.014,0.17,-0.032,0.0059,0.8,0,0,-4.9e+02,-0.0013,-0.0057,1.5e-05,0.028,-0.034,-0.12,0.2,-3.3e-05,0.43,-0.0013,-0.0019,0.00052,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.5e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31690000,0.98,-0.0071,-0.015,0.17,-0.036,0.0053,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.3e-05,0.028,-0.034,-0.12,0.2,-3.3e-05,0.43,-0.0014,-0.0019,0.0005,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31790000,0.99,-0.0074,-0.015,0.17,-0.026,0.0027,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.8e-05,0.028,-0.034,-0.12,0.2,-3.2e-05,0.43,-0.0015,-0.002,0.00053,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31890000,0.99,-0.0071,-0.015,0.17,-0.025,0.00049,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3.2e-05,0.028,-0.034,-0.12,0.2,-3.1e-05,0.43,-0.0016,-0.0021,0.00055,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31990000,0.99,-0.0074,-0.015,0.17,-0.017,-0.00059,0.79,0,0,-4.9e+02,-0.0013,-0.0057,2.9e-05,0.029,-0.035,-0.12,0.2,-3.2e-05,0.43,-0.0015,-0.0023,0.0006,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32090000,0.99,-0.0077,-0.014,0.17,-0.018,-0.004,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3e-05,0.029,-0.034,-0.12,0.2,-3.1e-05,0.43,-0.0016,-0.0024,0.00062,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32190000,0.99,-0.008,-0.015,0.17,-0.013,-0.0076,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.5e-05,0.029,-0.035,-0.12,0.2,-3e-05,0.43,-0.0016,-0.0025,0.00067,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32290000,0.99,-0.0079,-0.015,0.17,-0.012,-0.01,0.8,0,0,-4.9e+02,-0.0013,-0.0057,3e-05,0.029,-0.035,-0.12,0.2,-2.9e-05,0.43,-0.0017,-0.0026,0.00068,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32390000,0.99,-0.008,-0.015,0.17,-0.0061,-0.012,0.8,0,0,-4.9e+02,-0.0013,-0.0057,2.7e-05,0.03,-0.035,-0.12,0.2,-2.8e-05,0.43,-0.0017,-0.0028,0.00074,0,0,-4.9e+02,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32490000,0.99,-0.011,-0.013,0.17,0.019,-0.078,-0.076,0,0,-4.9e+02,-0.0013,-0.0057,2.3e-05,0.03,-0.035,-0.12,0.2,-2.9e-05,0.43,-0.0016,-0.0028,0.00073,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.014,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32590000,0.99,-0.011,-0.013,0.17,0.022,-0.079,-0.079,0,0,-4.9e+02,-0.0013,-0.0057,2.3e-05,0.03,-0.035,-0.12,0.2,-2.9e-05,0.43,-0.0016,-0.0024,0.0008,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32690000,0.99,-0.011,-0.013,0.17,0.017,-0.085,-0.08,0,0,-4.9e+02,-0.0013,-0.0057,2.1e-05,0.03,-0.035,-0.12,0.2,-2.9e-05,0.43,-0.0016,-0.0025,0.00079,0,0,-4.9e+02,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32790000,0.99,-0.011,-0.013,0.17,0.018,-0.084,-0.081,0,0,-4.9e+02,-0.0013,-0.0057,2e-05,0.03,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0016,-0.0023,0.00086,0,0,-4.9e+02,0.00028,0.00027,0.035,0.011,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32890000,0.99,-0.011,-0.013,0.17,0.017,-0.09,-0.083,0,0,-4.9e+02,-0.0013,-0.0057,2.4e-05,0.03,-0.035,-0.12,0.2,-2.7e-05,0.43,-0.0016,-0.0022,0.00088,0,0,-4.9e+02,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +32990000,0.98,-0.011,-0.013,0.17,0.017,-0.089,-0.082,0,0,-4.9e+02,-0.0013,-0.0057,2.5e-05,0.03,-0.035,-0.12,0.2,-2.5e-05,0.43,-0.0017,-0.0021,0.00094,0,0,-4.9e+02,0.00027,0.00027,0.035,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33090000,0.98,-0.011,-0.013,0.17,0.013,-0.094,-0.079,0,0,-4.9e+02,-0.0013,-0.0057,2.5e-05,0.03,-0.035,-0.12,0.2,-2.5e-05,0.43,-0.0017,-0.0021,0.00094,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33190000,0.98,-0.01,-0.013,0.17,0.011,-0.094,-0.078,0,0,-4.9e+02,-0.0014,-0.0057,1.6e-05,0.031,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0016,-0.0021,0.00096,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33290000,0.99,-0.01,-0.013,0.17,0.0078,-0.096,-0.078,0,0,-4.9e+02,-0.0014,-0.0057,2.7e-05,0.031,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0018,-0.0022,0.001,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33390000,0.98,-0.01,-0.013,0.17,0.0056,-0.091,-0.076,0,0,-4.9e+02,-0.0014,-0.0057,2e-05,0.033,-0.033,-0.12,0.2,-2e-05,0.43,-0.0018,-0.0021,0.0011,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.033 +33490000,0.99,-0.01,-0.013,0.17,0.0003,-0.094,-0.075,0,0,-4.9e+02,-0.0014,-0.0057,2.5e-05,0.033,-0.033,-0.12,0.2,-1.8e-05,0.43,-0.0019,-0.0023,0.0011,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.058 +33590000,0.99,-0.01,-0.013,0.17,-0.0025,-0.092,-0.072,0,0,-4.9e+02,-0.0014,-0.0057,2.4e-05,0.034,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.002,-0.0023,0.0011,0,0,-4.9e+02,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.083 +33690000,0.98,-0.01,-0.013,0.17,-0.0058,-0.095,-0.073,0,0,-4.9e+02,-0.0014,-0.0057,2.8e-05,0.034,-0.032,-0.12,0.2,-1.6e-05,0.43,-0.0019,-0.0022,0.0011,0,0,-4.9e+02,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.11 +33790000,0.98,-0.01,-0.013,0.17,-0.0077,-0.093,-0.068,0,0,-4.9e+02,-0.0014,-0.0057,1.8e-05,0.036,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.0019,-0.002,0.0012,0,0,-4.9e+02,0.00027,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.13 +33890000,0.98,-0.01,-0.013,0.17,-0.012,-0.093,-0.067,0,0,-4.9e+02,-0.0014,-0.0057,2.8e-05,0.036,-0.032,-0.12,0.2,-1.3e-05,0.43,-0.0019,-0.002,0.0012,0,0,-4.9e+02,0.00027,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.4e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.16 +33990000,0.98,-0.0099,-0.013,0.17,-0.013,-0.089,-0.064,0,0,-4.9e+02,-0.0014,-0.0057,1.6e-05,0.038,-0.031,-0.12,0.2,-1e-05,0.43,-0.0019,-0.0019,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.18 +34090000,0.98,-0.0098,-0.013,0.17,-0.017,-0.093,-0.062,0,0,-4.9e+02,-0.0014,-0.0057,1.8e-05,0.038,-0.031,-0.12,0.2,-1.1e-05,0.43,-0.0019,-0.0018,0.0012,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.21 +34190000,0.98,-0.0098,-0.013,0.17,-0.018,-0.088,-0.06,0,0,-4.9e+02,-0.0014,-0.0057,1.4e-05,0.04,-0.031,-0.12,0.2,-8.5e-06,0.43,-0.0018,-0.0017,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.23 +34290000,0.98,-0.0096,-0.014,0.17,-0.019,-0.092,-0.058,0,0,-4.9e+02,-0.0014,-0.0057,2.1e-05,0.04,-0.031,-0.12,0.2,-7.8e-06,0.43,-0.0019,-0.0017,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.26 +34390000,0.98,-0.0095,-0.014,0.17,-0.021,-0.086,-0.054,0,0,-4.9e+02,-0.0014,-0.0057,1.4e-05,0.041,-0.031,-0.12,0.2,-5.7e-06,0.43,-0.0018,-0.0016,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.28 +34490000,0.98,-0.0095,-0.014,0.17,-0.024,-0.089,-0.052,0,0,-4.9e+02,-0.0014,-0.0056,2.2e-05,0.041,-0.031,-0.12,0.2,-5.4e-06,0.43,-0.0019,-0.0016,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.31 +34590000,0.98,-0.0094,-0.013,0.17,-0.026,-0.082,0.74,0,0,-4.9e+02,-0.0014,-0.0056,1.5e-05,0.043,-0.03,-0.12,0.2,-2.9e-06,0.43,-0.0018,-0.0015,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 +34690000,0.98,-0.0094,-0.013,0.17,-0.031,-0.08,1.7,0,0,-4.9e+02,-0.0014,-0.0056,1.8e-05,0.043,-0.031,-0.12,0.2,-2.6e-06,0.43,-0.0019,-0.0016,0.0013,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.012,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.36 +34790000,0.98,-0.0093,-0.013,0.17,-0.034,-0.071,2.7,0,0,-4.9e+02,-0.0014,-0.0056,1.2e-05,0.045,-0.031,-0.12,0.2,6.3e-08,0.43,-0.0019,-0.0015,0.0014,0,0,-4.9e+02,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 +34890000,0.98,-0.0092,-0.013,0.17,-0.04,-0.069,3.7,0,0,-4.9e+02,-0.0014,-0.0056,1.5e-05,0.045,-0.031,-0.12,0.2,2.3e-07,0.43,-0.0019,-0.0015,0.0014,0,0,-4.9e+02,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 From 80a6e4b04be3bd02fb60aed292fa8f0581470a4e Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 1 Nov 2024 10:35:17 +0100 Subject: [PATCH 08/11] ekf2: rename resetAltitudeTo to initialiseAltitudeTo This is to better show that the altitude is also used to set the origin. --- .../ekf2/EKF/aid_sources/barometer/baro_height_control.cpp | 2 +- src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp | 2 +- src/modules/ekf2/EKF/ekf.cpp | 4 ++-- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/ekf_helper.cpp | 4 ++-- 5 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index 0f5bcd610c91..70cb041784bb 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -163,7 +163,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) _height_sensor_ref = HeightSensor::BARO; _information_events.flags.reset_hgt_to_baro = true; - resetAltitudeTo(measurement, measurement_var); + initialiseAltitudeTo(measurement, measurement_var); bias_est.reset(); } else { diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index 78a6d12f90a3..d31587461570 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -129,7 +129,7 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) _information_events.flags.reset_hgt_to_gps = true; - resetAltitudeTo(measurement, measurement_var); + initialiseAltitudeTo(measurement, measurement_var); bias_est.reset(); } else { diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index c3d4434a714d..a0df2a2ad710 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -296,7 +296,7 @@ bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const doubl return false; } - resetAltitudeTo(altitude, sq(epv)); + initialiseAltitudeTo(altitude, sq(epv)); return true; } @@ -370,7 +370,7 @@ bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const doubl const float obs_var = math::max(sq(epv), sq(0.01f)); ECL_INFO("reset height to external observation"); - resetAltitudeTo(gpos_corrected.altitude(), obs_var); + initialiseAltitudeTo(gpos_corrected.altitude(), obs_var); _last_known_gpos.setAltitude(gpos_corrected.altitude()); } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 47c6e10f94b6..41728ea0084f 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -649,7 +649,7 @@ class Ekf final : public EstimatorInterface bool setAltOrigin(float altitude, float vpos_var = NAN); bool resetLatLonTo(double latitude, double longitude, float hpos_var = NAN); - bool resetAltitudeTo(float altitude, float vpos_var = NAN); + bool initialiseAltitudeTo(float altitude, float vpos_var = NAN); // update quaternion states and covariances using an innovation, observation variance and Jacobian vector bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 33e63a6eb64a..e9332fdd901b 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -160,7 +160,7 @@ bool Ekf::resetGlobalPositionTo(const double latitude, const double longitude, c } // altitude is optional - resetAltitudeTo(altitude, vpos_var); + initialiseAltitudeTo(altitude, vpos_var); return true; } @@ -216,7 +216,7 @@ bool Ekf::resetLatLonTo(const double latitude, const double longitude, const flo return true; } -bool Ekf::resetAltitudeTo(const float altitude, const float vpos_var) +bool Ekf::initialiseAltitudeTo(const float altitude, const float vpos_var) { if (!checkAltitudeValidity(altitude)) { return false; From c4649fccecd8b189aeac3585d0313d6c2e118801 Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 14 Nov 2024 15:43:54 +0100 Subject: [PATCH 09/11] lla: move implementation to cpp file This reduces flash usage --- src/modules/ekf2/CMakeLists.txt | 1 + src/modules/ekf2/EKF/CMakeLists.txt | 1 + .../ekf2/EKF/lat_lon_alt/CMakeLists.txt | 44 ++++++- .../ekf2/EKF/lat_lon_alt/lat_lon_alt.cpp | 108 ++++++++++++++++++ .../ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp | 76 ++---------- .../ekf2/EKF/output_predictor/CMakeLists.txt | 2 +- 6 files changed, 164 insertions(+), 68 deletions(-) create mode 100644 src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.cpp diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 62e6f2910330..112b920ba251 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -277,6 +277,7 @@ px4_add_module( world_magnetic_model ${EKF_LIBS} + lat_lon_alt bias_estimator output_predictor UNITY_BUILD diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 27804ebcd88a..f6dc615f4e36 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -155,6 +155,7 @@ target_link_libraries(ecl_EKF PRIVATE bias_estimator geo + lat_lon_alt output_predictor world_magnetic_model ${EKF_LIBS} diff --git a/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt b/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt index bf2b3ebf536b..acd30f51f22f 100644 --- a/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt +++ b/src/modules/ekf2/EKF/lat_lon_alt/CMakeLists.txt @@ -1 +1,43 @@ -px4_add_unit_gtest(SRC test_lat_lon_alt.cpp LINKLIBS geo) +############################################################################ +# +# Copyright (c) 2024 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. +# +############################################################################ + +add_library(lat_lon_alt + lat_lon_alt.cpp + lat_lon_alt.hpp +) + +add_dependencies(lat_lon_alt prebuild_targets) +target_include_directories(lat_lon_alt PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) +target_compile_options(lat_lon_alt PRIVATE ${MAX_CUSTOM_OPT_LEVEL}) + +px4_add_unit_gtest(SRC test_lat_lon_alt.cpp LINKLIBS lat_lon_alt geo) diff --git a/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.cpp b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.cpp new file mode 100644 index 000000000000..93d347f2d73e --- /dev/null +++ b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.cpp @@ -0,0 +1,108 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include "lat_lon_alt.hpp" + +using matrix::Vector3f; +using matrix::Vector2d; + +Vector3f LatLonAlt::computeAngularRateNavFrame(const Vector3f &v_ned) const +{ + double r_n; + double r_e; + computeRadiiOfCurvature(_latitude_rad, r_n, r_e); + return Vector3f( + v_ned(1) / (static_cast(r_e) + _altitude), + -v_ned(0) / (static_cast(r_n) + _altitude), + -v_ned(1) * tanf(_latitude_rad) / (static_cast(r_e) + _altitude)); +} + +Vector2d LatLonAlt::deltaLatLonToDeltaXY(const double latitude, const float altitude) +{ + double r_n; + double r_e; + computeRadiiOfCurvature(latitude, r_n, r_e); + const double dn_dlat = r_n + static_cast(altitude); + const double de_dlon = (r_e + static_cast(altitude)) * cos(latitude); + + return Vector2d(dn_dlat, de_dlon); +} + +void LatLonAlt::computeRadiiOfCurvature(const double latitude, double &meridian_radius_of_curvature, + double &transverse_radius_of_curvature) +{ + const double tmp = 1.0 - pow(Wgs84::eccentricity * sin(latitude), 2); + const double sqrt_tmp = std::sqrt(tmp); + meridian_radius_of_curvature = Wgs84::meridian_radius_of_curvature_numerator / (tmp * tmp * sqrt_tmp); + transverse_radius_of_curvature = Wgs84::equatorial_radius / sqrt_tmp; +} + +LatLonAlt LatLonAlt::operator+(const matrix::Vector3f &delta_pos) const +{ + const matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(latitude_rad(), altitude()); + const double latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); + const double longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); + const float altitude = _altitude - delta_pos(2); + + LatLonAlt lla_new; + lla_new.setLatLonRad(latitude_rad, longitude_rad); + lla_new.setAltitude(altitude); + return lla_new; +} + +void LatLonAlt::operator+=(const matrix::Vector3f &delta_pos) +{ + matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); + _latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); + _longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); + _altitude -= delta_pos(2); +} + +void LatLonAlt::operator+=(const matrix::Vector2f &delta_pos) +{ + matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); + _latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); + _longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); +} + +matrix::Vector3f LatLonAlt::operator-(const LatLonAlt &lla) const +{ + const double delta_lat = matrix::wrap_pi(_latitude_rad - lla.latitude_rad()); + const double delta_lon = matrix::wrap_pi(_longitude_rad - lla.longitude_rad()); + const float delta_alt = _altitude - lla.altitude(); + + const matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); + return matrix::Vector3f(static_cast(delta_lat * d_lat_lon_to_d_xy(0)), + static_cast(delta_lon * d_lat_lon_to_d_xy(1)), + -delta_alt); +} diff --git a/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp index bb6a384d6ac6..548f6ee30d46 100644 --- a/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp +++ b/src/modules/ekf2/EKF/lat_lon_alt/lat_lon_alt.hpp @@ -73,33 +73,13 @@ class LatLonAlt void print() const { printf("latitude = %f (deg), longitude = %f (deg), altitude = %f (m)\n", _latitude_rad, _longitude_rad, (double)_altitude); } - void operator+=(const matrix::Vector3f &delta_pos) - { - matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); - _latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); - _longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); - _altitude -= delta_pos(2); - } - - void operator+=(const matrix::Vector2f &delta_pos) - { - matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); - _latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); - _longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); - } - - LatLonAlt operator+(const matrix::Vector3f &delta_pos) const - { - matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(latitude_rad(), altitude()); - const double latitude_rad = matrix::wrap_pi(_latitude_rad + static_cast(delta_pos(0)) / d_lat_lon_to_d_xy(0)); - const double longitude_rad = matrix::wrap_pi(_longitude_rad + static_cast(delta_pos(1)) / d_lat_lon_to_d_xy(1)); - const float altitude = _altitude - delta_pos(2); - - LatLonAlt lla_new; - lla_new.setLatLonRad(latitude_rad, longitude_rad); - lla_new.setAltitude(altitude); - return lla_new; - } + /* + * The plus and minus operators below use approximations and should only be used when the Cartesian component is small + */ + LatLonAlt operator+(const matrix::Vector3f &delta_pos) const; + void operator+=(const matrix::Vector3f &delta_pos); + void operator+=(const matrix::Vector2f &delta_pos); + matrix::Vector3f operator-(const LatLonAlt &lla) const; void operator=(const LatLonAlt &lla) { @@ -108,54 +88,18 @@ class LatLonAlt _altitude = lla.altitude(); } - matrix::Vector3f operator-(const LatLonAlt &lla) const - { - const double delta_lat = matrix::wrap_pi(_latitude_rad - lla.latitude_rad()); - const double delta_lon = matrix::wrap_pi(_longitude_rad - lla.longitude_rad()); - const float delta_alt = _altitude - lla.altitude(); - - const matrix::Vector2d d_lat_lon_to_d_xy = deltaLatLonToDeltaXY(_latitude_rad, _altitude); - return matrix::Vector3f(static_cast(delta_lat * d_lat_lon_to_d_xy(0)), - static_cast(delta_lon * d_lat_lon_to_d_xy(1)), - -delta_alt); - } - /* * Compute the angular rate of the local navigation frame at the current latitude and height * with respect to an inertial frame and resolved in the navigation frame */ - matrix::Vector3f computeAngularRateNavFrame(const matrix::Vector3f &v_ned) - { - double r_n; - double r_e; - computeRadiiOfCurvature(_latitude_rad, r_n, r_e); - return matrix::Vector3f( - v_ned(1) / (static_cast(r_e) + _altitude), - -v_ned(0) / (static_cast(r_n) + _altitude), - -v_ned(1) * tanf(_latitude_rad) / (static_cast(r_e) + _altitude)); - } + matrix::Vector3f computeAngularRateNavFrame(const matrix::Vector3f &v_ned) const; private: // Convert between curvilinear and cartesian errors - static matrix::Vector2d deltaLatLonToDeltaXY(const double latitude, const float altitude) - { - double r_n; - double r_e; - computeRadiiOfCurvature(latitude, r_n, r_e); - const double dn_dlat = r_n + static_cast(altitude); - const double de_dlon = (r_e + static_cast(altitude)) * cos(latitude); - - return matrix::Vector2d(dn_dlat, de_dlon); - } + static matrix::Vector2d deltaLatLonToDeltaXY(const double latitude, const float altitude); static void computeRadiiOfCurvature(const double latitude, double &meridian_radius_of_curvature, - double &transverse_radius_of_curvature) - { - const double tmp = 1.0 - pow(Wgs84::eccentricity * sin(latitude), 2); - const double sqrt_tmp = std::sqrt(tmp); - meridian_radius_of_curvature = Wgs84::meridian_radius_of_curvature_numerator / (tmp * tmp * sqrt_tmp); - transverse_radius_of_curvature = Wgs84::equatorial_radius / sqrt_tmp; - } + double &transverse_radius_of_curvature); struct Wgs84 { static constexpr double equatorial_radius = 6378137.0; diff --git a/src/modules/ekf2/EKF/output_predictor/CMakeLists.txt b/src/modules/ekf2/EKF/output_predictor/CMakeLists.txt index 701a5cb13f65..8d7b3e0607b3 100644 --- a/src/modules/ekf2/EKF/output_predictor/CMakeLists.txt +++ b/src/modules/ekf2/EKF/output_predictor/CMakeLists.txt @@ -36,4 +36,4 @@ add_library(output_predictor output_predictor.h ) -add_dependencies(output_predictor prebuild_targets) +add_dependencies(output_predictor prebuild_targets lat_lon_alt) From 83e45893db21142a92ff448577aefced3239e2e1 Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 22 Nov 2024 12:03:11 +0100 Subject: [PATCH 10/11] ekf2: do not inline getPosition --- src/modules/ekf2/EKF/estimator_interface.cpp | 20 ++++++++++++++++++++ src/modules/ekf2/EKF/estimator_interface.h | 20 +------------------- 2 files changed, 21 insertions(+), 19 deletions(-) diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index f7a6c70dec39..84ced94c8004 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -568,6 +568,26 @@ bool EstimatorInterface::initialise_interface(uint64_t timestamp) return true; } +Vector3f EstimatorInterface::getPosition() const +{ + LatLonAlt lla = _output_predictor.getLatLonAlt(); + float x; + float y; + + if (_local_origin_lat_lon.isInitialized()) { + _local_origin_lat_lon.project(lla.latitude_deg(), lla.longitude_deg(), x, y); + + } else { + MapProjection zero_ref; + zero_ref.initReference(0.0, 0.0); + zero_ref.project(lla.latitude_deg(), lla.longitude_deg(), x, y); + } + + const float z = -(lla.altitude() - getEkfGlobalOriginAltitude()); + + return Vector3f(x, y, z); +} + bool EstimatorInterface::isOnlyActiveSourceOfHorizontalAiding(const bool aiding_flag) const { return aiding_flag && !isOtherSourceOfHorizontalAidingThan(aiding_flag); diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 5322fe09976c..90c26d608392 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -242,25 +242,7 @@ class EstimatorInterface Vector3f getVelocity() const { return _output_predictor.getVelocity(); } const Vector3f &getVelocityDerivative() const { return _output_predictor.getVelocityDerivative(); } float getVerticalPositionDerivative() const { return _output_predictor.getVerticalPositionDerivative(); } - Vector3f getPosition() const - { - LatLonAlt lla = _output_predictor.getLatLonAlt(); - float x; - float y; - - if (_local_origin_lat_lon.isInitialized()) { - _local_origin_lat_lon.project(lla.latitude_deg(), lla.longitude_deg(), x, y); - - } else { - MapProjection zero_ref; - zero_ref.initReference(0.0, 0.0); - zero_ref.project(lla.latitude_deg(), lla.longitude_deg(), x, y); - } - - const float z = -(lla.altitude() - getEkfGlobalOriginAltitude()); - - return Vector3f(x, y, z); - } + Vector3f getPosition() const; LatLonAlt getLatLonAlt() const { return _output_predictor.getLatLonAlt(); } const Vector3f &getOutputTrackingError() const { return _output_predictor.getOutputTrackingError(); } From fb815f39ae05e7a1cc818dc750361e0ad5b048fa Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 22 Nov 2024 12:21:16 +0100 Subject: [PATCH 11/11] ekf2: resetHeightTo -> resetAltitudeTo The vertical position state is now an altitude, not just a local height --- .../ekf2/EKF/aid_sources/barometer/baro_height_control.cpp | 2 +- .../EKF/aid_sources/external_vision/ev_height_control.cpp | 6 +++--- src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp | 2 +- .../ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp | 2 +- .../EKF/aid_sources/range_finder/range_height_control.cpp | 4 ++-- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/ekf_helper.cpp | 4 ++-- src/modules/ekf2/EKF/position_fusion.cpp | 2 +- 8 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp index 70cb041784bb..c645afd9d5c7 100644 --- a/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/barometer/baro_height_control.cpp @@ -131,7 +131,7 @@ void Ekf::controlBaroHeightFusion(const imuSample &imu_sample) ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_baro = true; - resetHeightTo(_baro_lpf.getState() - bias_est.getBias(), measurement_var); + resetAltitudeTo(_baro_lpf.getState() - bias_est.getBias(), measurement_var); bias_est.setBias(-_gpos.altitude() + _baro_lpf.getState()); // reset vertical velocity if no valid sources available diff --git a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp index f62be7575fdc..232ecd375284 100644 --- a/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/external_vision/ev_height_control.cpp @@ -117,7 +117,7 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp if (_height_sensor_ref == HeightSensor::EV) { _information_events.flags.reset_hgt_to_ev = true; - resetHeightTo(-measurement, measurement_var); + resetAltitudeTo(-measurement, measurement_var); bias_est.reset(); } else { @@ -146,7 +146,7 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp // All height sources are failing ECL_WARN("%s fusion reset required, all height sources failing", AID_SRC_NAME); _information_events.flags.reset_hgt_to_ev = true; - resetHeightTo(-measurement - bias_est.getBias(), measurement_var); + resetAltitudeTo(-measurement - bias_est.getBias(), measurement_var); bias_est.setBias(_gpos.altitude() + measurement); aid_src.time_last_fuse = _time_delayed_us; @@ -170,7 +170,7 @@ void Ekf::controlEvHeightFusion(const imuSample &imu_sample, const extVisionSamp if (_params.height_sensor_ref == static_cast(HeightSensor::EV)) { ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME); _information_events.flags.reset_hgt_to_ev = true; - resetHeightTo(-measurement, measurement_var); + resetAltitudeTo(-measurement, measurement_var); _height_sensor_ref = HeightSensor::EV; bias_est.reset(); diff --git a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp index 4ff4e67d6cd9..8fa2dfb62592 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_height_control.cpp @@ -110,7 +110,7 @@ void Ekf::resetHeightToLastKnown() { _information_events.flags.reset_pos_to_last_known = true; ECL_INFO("reset height to last known (%.3f)", (double)_last_known_gpos.altitude()); - resetHeightTo(_last_known_gpos.altitude(), sq(_params.pos_noaid_noise)); + resetAltitudeTo(_last_known_gpos.altitude(), sq(_params.pos_noaid_noise)); } void Ekf::stopFakeHgtFusion() diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp index d31587461570..c936442b1405 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gnss_height_control.cpp @@ -105,7 +105,7 @@ void Ekf::controlGnssHeightFusion(const gnssSample &gps_sample) ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_gps = true; - resetHeightTo(measurement, measurement_var); + resetAltitudeTo(measurement, measurement_var); bias_est.setBias(-_gpos.altitude() + measurement); aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp index 2598f3a3318c..fec1fd9d8e85 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp @@ -148,7 +148,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) _height_sensor_ref = HeightSensor::RANGE; _information_events.flags.reset_hgt_to_rng = true; - resetHeightTo(aid_src.observation, aid_src.observation_variance); + resetAltitudeTo(aid_src.observation, aid_src.observation_variance); _state.terrain = 0.f; _control_status.flags.rng_hgt = true; stopRngTerrFusion(); @@ -180,7 +180,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME); _information_events.flags.reset_hgt_to_rng = true; - resetHeightTo(aid_src.observation - _state.terrain); + resetAltitudeTo(aid_src.observation - _state.terrain); // reset vertical velocity if no valid sources available if (!isVerticalVelocityAidingActive()) { diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 41728ea0084f..f42493652ecc 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -725,7 +725,7 @@ class Ekf final : public EstimatorInterface bool isHeightResetRequired() const; - void resetHeightTo(float new_altitude, float new_vert_pos_var = NAN); + void resetAltitudeTo(float new_altitude, float new_vert_pos_var = NAN); void updateVerticalPositionResetStatus(const float delta_z); void resetVerticalVelocityToZero(); diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index e9332fdd901b..9638abeb694c 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -137,7 +137,7 @@ bool Ekf::setAltOrigin(const float altitude, const float vpos_var) if (!PX4_ISFINITE(_local_origin_alt) && isLocalVerticalPositionValid()) { const float local_alt_prev = _gpos.altitude(); _local_origin_alt = altitude; - resetHeightTo(local_alt_prev + _local_origin_alt); + resetAltitudeTo(local_alt_prev + _local_origin_alt); } else { const float delta_origin_alt = altitude - _local_origin_alt; @@ -235,7 +235,7 @@ bool Ekf::initialiseAltitudeTo(const float altitude, const float vpos_var) ECL_INFO("Origin alt=%.3f", (double)_local_origin_alt); } - resetHeightTo(altitude, vpos_var); + resetAltitudeTo(altitude, vpos_var); return true; } diff --git a/src/modules/ekf2/EKF/position_fusion.cpp b/src/modules/ekf2/EKF/position_fusion.cpp index e4c16b49415b..7d874e654081 100644 --- a/src/modules/ekf2/EKF/position_fusion.cpp +++ b/src/modules/ekf2/EKF/position_fusion.cpp @@ -182,7 +182,7 @@ void Ekf::resetHorizontalPositionTo(const Vector2f &new_pos, resetHorizontalPositionTo(new_latitude, new_longitude, new_horz_pos_var); } -void Ekf::resetHeightTo(const float new_altitude, float new_vert_pos_var) +void Ekf::resetAltitudeTo(const float new_altitude, float new_vert_pos_var) { const float old_altitude = _gpos.altitude(); _gpos.setAltitude(new_altitude);