From be4d0d351c47dfeb37d1fd760d437cabbcaf0b60 Mon Sep 17 00:00:00 2001 From: sbtjagu <145494402+sbtjagu@users.noreply.github.com> Date: Tue, 27 Aug 2024 13:35:48 +0200 Subject: [PATCH 01/31] ackermann: add speed waypoint support and fix delay detection (#23572) --- .../RoverAckermannGuidance.cpp | 44 +++++++++++-------- .../RoverAckermannGuidance.hpp | 4 ++ 2 files changed, 30 insertions(+), 18 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index 1acaebb6386f..48890323bbb4 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -60,6 +60,14 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c { updateSubscriptions(); + // Distances to waypoints + _distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _prev_wp(0), _prev_wp(1)); + _distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _curr_wp(0), _curr_wp(1)); + _distance_to_next_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _next_wp(0), _next_wp(1)); + // Catch return to launch if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { _mission_finished = _distance_to_next_wp < _acceptance_radius; @@ -74,7 +82,8 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c _desired_speed = 0.f; } else { // Regular guidance algorithm - _desired_speed = calcDesiredSpeed(_param_ra_miss_vel_def.get(), _param_ra_miss_vel_min.get(), + + _desired_speed = calcDesiredSpeed(_wp_max_desired_vel, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_gain.get(), _distance_to_prev_wp, _distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _param_ra_max_accel.get(), _param_ra_max_jerk.get(), nav_state); @@ -156,40 +165,32 @@ void RoverAckermannGuidance::updateWaypointsAndAcceptanceRadius() _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); // Global waypoint coordinates - Vector2d prev_wp = _curr_pos.isAllFinite() ? _curr_pos : Vector2d(0, 0); // Fallback if previous waypoint is invalid - Vector2d curr_wp(0, 0); - Vector2d next_wp = _home_position.isAllFinite() ? _home_position : Vector2d(0, 0); // Enables corner slow down with RTL + _prev_wp = _curr_pos.isAllFinite() ? _curr_pos : Vector2d(0, 0); // Fallback if previous waypoint is invalid + _curr_wp = Vector2d(0, 0); + _next_wp = _home_position.isAllFinite() ? _home_position : Vector2d(0, 0); // Enables corner slow down with RTL if (position_setpoint_triplet.current.valid && PX4_ISFINITE(position_setpoint_triplet.current.lat) && PX4_ISFINITE(position_setpoint_triplet.current.lon)) { - curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); + _curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); } if (position_setpoint_triplet.previous.valid && PX4_ISFINITE(position_setpoint_triplet.previous.lat) && PX4_ISFINITE(position_setpoint_triplet.previous.lon)) { - prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon); + _prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon); } if (position_setpoint_triplet.next.valid && PX4_ISFINITE(position_setpoint_triplet.next.lat) && PX4_ISFINITE(position_setpoint_triplet.next.lon)) { - next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon); + _next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon); } - // Distances to waypoints - _distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - prev_wp(0), prev_wp(1)); - _distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - curr_wp(0), curr_wp(1)); - _distance_to_next_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - next_wp(0), next_wp(1)); - // NED waypoint coordinates - _curr_wp_ned = _global_ned_proj_ref.project(curr_wp(0), curr_wp(1)); - _prev_wp_ned = _global_ned_proj_ref.project(prev_wp(0), prev_wp(1)); - _next_wp_ned = _global_ned_proj_ref.project(next_wp(0), next_wp(1)); + _curr_wp_ned = _global_ned_proj_ref.project(_curr_wp(0), _curr_wp(1)); + _prev_wp_ned = _global_ned_proj_ref.project(_prev_wp(0), _prev_wp(1)); + _next_wp_ned = _global_ned_proj_ref.project(_next_wp(0), _next_wp(1)); // Update acceptance radius _prev_acceptance_radius = _acceptance_radius; @@ -201,6 +202,13 @@ void RoverAckermannGuidance::updateWaypointsAndAcceptanceRadius() } else { _acceptance_radius = _param_nav_acc_rad.get(); } + + if (position_setpoint_triplet.current.cruising_speed > 0.f) { + _wp_max_desired_vel = math::constrain(position_setpoint_triplet.current.cruising_speed, 0.f, _param_ra_max_speed.get()); + + } else { + _wp_max_desired_vel = _param_ra_miss_vel_def.get(); + } } float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index 23f63ed9280e..de5ef587807c 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -205,11 +205,15 @@ class RoverAckermannGuidance : public ModuleParams Vector2f _curr_wp_ned{}; Vector2f _prev_wp_ned{}; Vector2f _next_wp_ned{}; + Vector2d _curr_wp{}; + Vector2d _prev_wp{}; + Vector2d _next_wp{}; float _distance_to_prev_wp{0.f}; float _distance_to_curr_wp{0.f}; float _distance_to_next_wp{0.f}; float _acceptance_radius{0.5f}; float _prev_acceptance_radius{0.5f}; + float _wp_max_desired_vel{0.f}; bool _mission_finished{false}; // Parameters From bbcf741e9ea8743458df8be9a9317e2913f5b695 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 31 May 2024 15:37:05 -0400 Subject: [PATCH 02/31] ekf2: make mag control responsible for WMM - this further untangles mag control (which requires the WMM) from GPS --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 18 +-- .../aid_sources/magnetometer/mag_control.cpp | 134 ++++++++++++++---- .../aid_sources/magnetometer/mag_fusion.cpp | 55 +++---- src/modules/ekf2/EKF/ekf.h | 8 +- src/modules/ekf2/EKF/ekf_helper.cpp | 37 +---- src/modules/ekf2/EKF/estimator_interface.h | 21 +-- src/modules/ekf2/test/test_EKF_airspeed.cpp | 2 +- src/modules/ekf2/test/test_EKF_basics.cpp | 1 - 8 files changed, 155 insertions(+), 121 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 94fa6f04f381..4467ff9f7e28 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -41,10 +41,6 @@ #include "ekf.h" -#if defined(CONFIG_EKF2_MAGNETOMETER) -# include -#endif // CONFIG_EKF2_MAGNETOMETER - #include // GPS pre-flight check bit locations @@ -89,20 +85,20 @@ void Ekf::collect_gps(const gnssSample &gps) _gpos_origin_eph = gps.hacc; _gpos_origin_epv = gps.vacc; + _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(gps.lat))); + _information_events.flags.gps_checks_passed = true; - ECL_INFO("GPS checks passed"); - } - if ((isTimedOut(_wmm_gps_time_last_checked, 1e6)) || (_wmm_gps_time_last_set == 0)) { - // a rough 2D fix is sufficient to lookup declination + 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 || !_NED_origin_initialised)) { - updateWmm(gps.lat, gps.lon); _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); } - - _wmm_gps_time_last_checked = _time_delayed_us; } } 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 0e42006b249d..f36eba1dc612 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -39,6 +39,8 @@ #include "ekf.h" #include +#include + #include void Ekf::controlMagFusion(const imuSample &imu_sample) @@ -76,15 +78,43 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) _mag_counter++; } + // check for WMM update periodically or if global origin has changed + bool wmm_updated = false; + + if (global_origin().isInitialized()) { + + bool origin_newer_than_last_mag = (global_origin().getProjectionReferenceTimestamp() > aid_src.time_last_fuse); + + if (global_origin_valid() + && (origin_newer_than_last_mag || (local_position_is_valid() && 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)) { + wmm_updated = true; + } + + _wmm_mag_time_last_checked = _time_delayed_us; + + } else if (origin_newer_than_last_mag) { + // use global origin to update WMM + if (updateWorldMagneticModel(global_origin().getProjectionReferenceLat(), + global_origin().getProjectionReferenceLon()) + ) { + wmm_updated = true; + } + } + } + // if enabled, use knowledge of theoretical magnetic field vector to calculate a synthetic magnetomter Z component value. // this is useful if there is a lot of interference on the sensor measurement. if (_params.synthesize_mag_z && (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) - && (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) + && (_wmm_earth_field_gauss.isAllFinite() && _wmm_earth_field_gauss.longerThan(0.f)) ) { - const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) - * Vector3f(_mag_strength_gps, 0, 0); - - mag_sample.mag(2) = calculate_synthetic_mag_z_measurement(mag_sample.mag, mag_earth_pred); + mag_sample.mag(2) = calculate_synthetic_mag_z_measurement(mag_sample.mag, _wmm_earth_field_gauss); _control_status.flags.synthetic_mag_z = true; @@ -140,8 +170,6 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) checkMagHeadingConsistency(mag_sample); - // WMM update can occur on the last epoch, just after mag fusion - const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse); const bool using_ne_aiding = _control_status.flags.gps || _control_status.flags.aux_gpos; @@ -203,7 +231,21 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) } if (_control_status.flags.mag_dec) { - fuseDeclination(0.5f); + + if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) + && PX4_ISFINITE(_wmm_declination_rad) + ) { + fuseDeclination(_wmm_declination_rad, 0.5f); + + } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) + && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) + ) { + + fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f); + + } else { + _control_status.flags.mag_dec = false; + } } } @@ -333,24 +375,21 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) resetMagCov(); // if world magnetic model (inclination, declination, strength) available then use it to reset mag states - if (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) { - + if (_wmm_earth_field_gauss.longerThan(0.f) && _wmm_earth_field_gauss.isAllFinite()) { // use expected earth field to reset states - const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) - * Vector3f(_mag_strength_gps, 0, 0); // mag_B: reset if (!reset_heading && _control_status.flags.yaw_align) { // mag_B: reset using WMM const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); - _state.mag_B = mag - (R_to_body * mag_earth_pred); + _state.mag_B = mag - (R_to_body * _wmm_earth_field_gauss); } else { _state.mag_B.zero(); } // mag_I: reset, skipped if no change in state and variance good - _state.mag_I = mag_earth_pred; + _state.mag_I = _wmm_earth_field_gauss; if (reset_heading) { resetMagHeading(mag); @@ -451,8 +490,8 @@ bool Ekf::checkMagField(const Vector3f &mag_sample) _mag_strength = mag_sample.length(); if (_params.mag_check & static_cast(MagCheckMask::STRENGTH)) { - if (PX4_ISFINITE(_mag_strength_gps)) { - if (!isMeasuredMatchingExpected(_mag_strength, _mag_strength_gps, _params.mag_check_strength_tolerance_gs)) { + if (PX4_ISFINITE(_wmm_field_strength_gauss)) { + if (!isMeasuredMatchingExpected(_mag_strength, _wmm_field_strength_gauss, _params.mag_check_strength_tolerance_gs)) { _control_status.flags.mag_field_disturbed = true; is_check_failing = true; } @@ -475,9 +514,9 @@ bool Ekf::checkMagField(const Vector3f &mag_sample) _mag_inclination = asinf(mag_earth(2) / fmaxf(mag_earth.norm(), 1e-4f)); if (_params.mag_check & static_cast(MagCheckMask::INCLINATION)) { - if (PX4_ISFINITE(_mag_inclination_gps)) { + if (PX4_ISFINITE(_wmm_inclination_rad)) { const float inc_tol_rad = radians(_params.mag_check_inclination_tolerance_deg); - const float inc_error_rad = wrap_pi(_mag_inclination - _mag_inclination_gps); + const float inc_error_rad = wrap_pi(_mag_inclination - _wmm_inclination_rad); if (fabsf(inc_error_rad) > inc_tol_rad) { _control_status.flags.mag_field_disturbed = true; @@ -549,13 +588,60 @@ float Ekf::getMagDeclination() // Use value consistent with earth field state return atan2f(_state.mag_I(1), _state.mag_I(0)); - } else if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) { - // use parameter value until GPS is available, then use value returned by geo library - if (PX4_ISFINITE(_mag_declination_gps)) { - return _mag_declination_gps; + } else if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) + && PX4_ISFINITE(_wmm_declination_rad) + ) { + // if available use value returned by geo library + return _wmm_declination_rad; + + } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) + && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) + ) { + // using saved mag declination + return math::radians(_params.mag_declination_deg); + } + + // otherwise unavailable + return 0.f; +} + +bool Ekf::updateWorldMagneticModel(const double latitude_deg, const double longitude_deg) +{ + // set the magnetic field data returned by the geo library using the current GPS position + const float declination_rad = math::radians(get_mag_declination_degrees(latitude_deg, longitude_deg)); + const float inclination_rad = math::radians(get_mag_inclination_degrees(latitude_deg, longitude_deg)); + const float strength_gauss = get_mag_strength_gauss(latitude_deg, longitude_deg); + + if (PX4_ISFINITE(declination_rad) && PX4_ISFINITE(inclination_rad) && PX4_ISFINITE(strength_gauss)) { + + const bool declination_changed = (fabsf(declination_rad - _wmm_declination_rad) > math::radians(1.f)); + const bool inclination_changed = (fabsf(inclination_rad - _wmm_inclination_rad) > math::radians(1.f)); + const bool strength_changed = (fabsf(strength_gauss - _wmm_field_strength_gauss) > 0.01f); + + if (!PX4_ISFINITE(_wmm_declination_rad) + || !PX4_ISFINITE(_wmm_inclination_rad) + || !PX4_ISFINITE(_wmm_field_strength_gauss) + || !_wmm_earth_field_gauss.longerThan(0.f) + || !_wmm_earth_field_gauss.isAllFinite() + || declination_changed + || inclination_changed + || strength_changed + ) { + + ECL_DEBUG("WMM declination updated %.3f -> %.3f deg (lat=%.6f, lon=%.6f)", + (double)math::degrees(_wmm_declination_rad), (double)math::degrees(declination_rad), + (double)latitude_deg, (double)longitude_deg + ); + + _wmm_declination_rad = declination_rad; + _wmm_inclination_rad = inclination_rad; + _wmm_field_strength_gauss = strength_gauss; + + _wmm_earth_field_gauss = Dcmf(Eulerf(0, -inclination_rad, declination_rad)) * Vector3f(strength_gauss, 0, 0); + + return true; } } - // otherwise use the parameter value - return math::radians(_params.mag_declination_deg); + return false; } diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index acd16578c54f..887caf20dd15 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -150,51 +150,34 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima return false; } -bool Ekf::fuseDeclination(float decl_sigma) +bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma) { - float decl_measurement = NAN; + // observation variance (rad**2) + const float R_DECL = sq(decl_sigma); - if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) - && PX4_ISFINITE(_mag_declination_gps) - ) { - decl_measurement = _mag_declination_gps; + VectorState H; + float decl_pred; + float innovation_variance; - } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) - && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) - ) { - decl_measurement = math::radians(_params.mag_declination_deg); - } - - if (PX4_ISFINITE(decl_measurement)) { - - // observation variance (rad**2) - const float R_DECL = sq(decl_sigma); - - VectorState H; - float decl_pred; - float innovation_variance; - - sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance, - &H); - - const float innovation = wrap_pi(decl_pred - decl_measurement); + sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, + &decl_pred, &innovation_variance, &H); - if (innovation_variance < R_DECL) { - // variance calculation is badly conditioned - return false; - } + const float innovation = wrap_pi(decl_pred - decl_measurement_rad); - // Calculate the Kalman gains - VectorState Kfusion = P * H / innovation_variance; + if (innovation_variance < R_DECL) { + // variance calculation is badly conditioned + _fault_status.flags.bad_mag_decl = true; + return false; + } - const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); + // Calculate the Kalman gains + VectorState Kfusion = P * H / innovation_variance; - _fault_status.flags.bad_mag_decl = !is_fused; + const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); - return is_fused; - } + _fault_status.flags.bad_mag_decl = !is_fused; - return false; + return is_fused; } float Ekf::calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index e6c182171aff..edf50329bb49 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -259,7 +259,6 @@ class Ekf final : public EstimatorInterface // return true if the origin is valid bool getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const; bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = 0.f, float epv = 0.f); - void updateWmm(double lat, double lon); // 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; @@ -466,6 +465,9 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_MAGNETOMETER) + // set the magnetic field data returned by the geo library using position + bool updateWorldMagneticModel(const double latitude_deg, const double longitude_deg); + const auto &aid_src_mag() const { return _aid_src_mag; } #endif // CONFIG_EKF2_MAGNETOMETER @@ -770,8 +772,8 @@ class Ekf final : public EstimatorInterface bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement - // argument passed in is the declination uncertainty in radians - bool fuseDeclination(float decl_sigma); + // declination uncertainty in radians + bool fuseDeclination(float decl_measurement_rad, float decl_sigma); #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 9df8fe1da239..01821fd97bb8 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -96,13 +96,13 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _pos_ref.initReference(latitude, longitude, _time_delayed_us); _gps_alt_ref = altitude; - updateWmm(current_lat, current_lon); - _gpos_origin_eph = eph; _gpos_origin_epv = epv; _NED_origin_initialised = true; + _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(latitude))); + if (current_pos_available) { // reset horizontal position if we already have a global origin Vector2f position = _pos_ref.project(current_lat, current_lon); @@ -131,39 +131,6 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons return false; } -void Ekf::updateWmm(const double lat, const double lon) -{ -#if defined(CONFIG_EKF2_MAGNETOMETER) - - // set the magnetic field data returned by the geo library using the current GPS position - const float mag_declination_gps = math::radians(get_mag_declination_degrees(lat, lon)); - const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(lat, lon)); - const float mag_strength_gps = get_mag_strength_gauss(lat, lon); - - if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { - - const bool mag_declination_changed = (fabsf(mag_declination_gps - _mag_declination_gps) > math::radians(1.f)); - const bool mag_inclination_changed = (fabsf(mag_inclination_gps - _mag_inclination_gps) > math::radians(1.f)); - - if ((_wmm_gps_time_last_set == 0) - || !PX4_ISFINITE(_mag_declination_gps) - || !PX4_ISFINITE(_mag_inclination_gps) - || !PX4_ISFINITE(_mag_strength_gps) - || mag_declination_changed - || mag_inclination_changed - ) { - _mag_declination_gps = mag_declination_gps; - _mag_inclination_gps = mag_inclination_gps; - _mag_strength_gps = mag_strength_gps; - - _wmm_gps_time_last_set = _time_delayed_us; - } - } - -#endif // CONFIG_EKF2_MAGNETOMETER -} - - void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const { float eph = INFINITY; diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 57e6fc06b029..302d113f8d12 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -250,7 +250,7 @@ class EstimatorInterface bool get_mag_decl_deg(float &val) const { if (_NED_origin_initialised && (_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL)) { - val = math::degrees(_mag_declination_gps); + val = math::degrees(_wmm_declination_rad); return true; } else { @@ -261,7 +261,7 @@ class EstimatorInterface bool get_mag_inc_deg(float &val) const { if (_NED_origin_initialised) { - val = math::degrees(_mag_inclination_gps); + val = math::degrees(_wmm_inclination_rad); return true; } else { @@ -272,9 +272,9 @@ class EstimatorInterface void get_mag_checks(float &inc_deg, float &inc_ref_deg, float &strength_gs, float &strength_ref_gs) const { inc_deg = math::degrees(_mag_inclination); - inc_ref_deg = math::degrees(_mag_inclination_gps); + inc_ref_deg = math::degrees(_wmm_inclination_rad); strength_gs = _mag_strength; - strength_ref_gs = _mag_strength_gps; + strength_ref_gs = _wmm_field_strength_gauss; } #endif // CONFIG_EKF2_MAGNETOMETER @@ -451,13 +451,14 @@ class EstimatorInterface // allocate data buffers and initialize interface variables bool initialise_interface(uint64_t timestamp); - uint64_t _wmm_gps_time_last_checked{0}; // time WMM last checked - uint64_t _wmm_gps_time_last_set{0}; // time WMM last set - #if defined(CONFIG_EKF2_MAGNETOMETER) - float _mag_declination_gps {NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad) - float _mag_inclination_gps{NAN}; // magnetic inclination returned by the geo library using the last valid GPS position (rad) - float _mag_strength_gps{NAN}; // magnetic strength returned by the geo library using the last valid GPS position (T) + uint64_t _wmm_mag_time_last_checked {0}; // time WMM update last checked by mag control + + float _wmm_declination_rad{NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad) + float _wmm_inclination_rad{NAN}; // magnetic inclination returned by the geo library using the last valid GPS position (rad) + float _wmm_field_strength_gauss{NAN}; // magnetic strength returned by the geo library using the last valid GPS position (Gauss) + + Vector3f _wmm_earth_field_gauss{}; // expected magnetic field vector from the last valid GPS position (Gauss) float _mag_inclination{NAN}; float _mag_strength{NAN}; diff --git a/src/modules/ekf2/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp index 61865dfc7a9a..d1bd54a13b21 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -199,7 +199,7 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) EXPECT_TRUE(_ekf_wrapper.isWindVelocityEstimated()); const Vector3f vel = _ekf->getVelocity(); - EXPECT_NEAR(vel.norm(), airspeed_body.norm(), 1e-3f); + EXPECT_NEAR(vel.norm(), airspeed_body.norm(), 1e-2f); const Vector2f vel_wind_earth = _ekf->getWindVelocity(); EXPECT_NEAR(vel_wind_earth(0), 0.f, .1f); EXPECT_NEAR(vel_wind_earth(1), 0.f, .1f); diff --git a/src/modules/ekf2/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp index e95443344235..0d34e676cbb9 100644 --- a/src/modules/ekf2/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -108,7 +108,6 @@ TEST_F(EkfBasicsTest, initialControlMode) EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_hdg); EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_3D); EXPECT_EQ(1, (int) _ekf->control_status_flags().mag); - EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_dec); EXPECT_EQ(0, (int) _ekf->control_status_flags().in_air); EXPECT_EQ(0, (int) _ekf->control_status_flags().wind); EXPECT_EQ(1, (int) _ekf->control_status_flags().baro_hgt); From 9d57a3c02f80de3945678a51cb6510e7e2e4ff1f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 13:33:40 -0400 Subject: [PATCH 03/31] ekf2: split resetMagCov() and skip mag reset if negligible change --- .../aid_sources/magnetometer/mag_control.cpp | 73 +++++++++++-------- .../aid_sources/magnetometer/mag_fusion.cpp | 3 +- src/modules/ekf2/EKF/covariance.cpp | 13 +++- src/modules/ekf2/EKF/ekf.h | 3 +- 4 files changed, 57 insertions(+), 35 deletions(-) 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 f36eba1dc612..99da95e5a188 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -68,7 +68,9 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) _control_status.flags.mag_fault = false; _state.mag_B.zero(); - resetMagCov(); + resetMagBiasCov(); + + stopMagFusion(); _mag_lpf.reset(mag_sample.mag); _mag_counter = 1; @@ -210,7 +212,7 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if (continuing_conditions_passing && _control_status.flags.yaw_align) { - if (mag_sample.reset || checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) { + if (checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) { ECL_INFO("reset to %s", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = imu_sample.time_us; @@ -313,6 +315,9 @@ void Ekf::stopMagFusion() if (_control_status.flags.mag) { ECL_INFO("stopping mag fusion"); + resetMagEarthCov(); + resetMagBiasCov(); + if (_control_status.flags.yaw_align && (_control_status.flags.mag_3D || _control_status.flags.mag_hdg)) { // reset yaw alignment from mag unless using GNSS aiding const bool using_ne_aiding = _control_status.flags.gps || _control_status.flags.aux_gpos; @@ -371,26 +376,36 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) const Vector3f mag_I_before_reset = _state.mag_I; const Vector3f mag_B_before_reset = _state.mag_B; - // reset covariances to default - resetMagCov(); + static constexpr float kMagEarthMinGauss = 0.01f; // minimum difference in mag earth field strength for reset (Gauss) // if world magnetic model (inclination, declination, strength) available then use it to reset mag states if (_wmm_earth_field_gauss.longerThan(0.f) && _wmm_earth_field_gauss.isAllFinite()) { // use expected earth field to reset states - // mag_B: reset + // mag_I: reset, skipped if negligible change in state + const Vector3f mag_I = _wmm_earth_field_gauss; + bool mag_I_reset = false; + + if ((_state.mag_I - mag_I).longerThan(kMagEarthMinGauss)) { + _state.mag_I = mag_I; + resetMagEarthCov(); + mag_I_reset = true; + } + + // mag_B: reset, skipped if mag_I didn't change if (!reset_heading && _control_status.flags.yaw_align) { - // mag_B: reset using WMM - const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); - _state.mag_B = mag - (R_to_body * _wmm_earth_field_gauss); + if (mag_I_reset) { + // mag_B: reset using WMM + const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); + _state.mag_B = mag - (R_to_body * _wmm_earth_field_gauss); + resetMagBiasCov(); + } // otherwise keep existing mag_B state (!mag_I_reset) } else { _state.mag_B.zero(); + resetMagBiasCov(); } - // mag_I: reset, skipped if no change in state and variance good - _state.mag_I = _wmm_earth_field_gauss; - if (reset_heading) { resetMagHeading(mag); } @@ -398,34 +413,32 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) } else { // mag_B: reset _state.mag_B.zero(); + resetMagBiasCov(); - // Use the magnetometer measurement to reset the field states + // Use the magnetometer measurement to reset the heading if (reset_heading) { resetMagHeading(mag); } - // mag_I: use the last magnetometer measurements to reset the field states - _state.mag_I = _R_to_earth * mag; - } + // mag_I: use the last magnetometer measurement to reset the field states + const Vector3f mag_I = _R_to_earth * mag; - if (!mag_I_before_reset.longerThan(0.f)) { - ECL_INFO("initializing mag I [%.3f, %.3f, %.3f], mag B [%.3f, %.3f, %.3f]", - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), - (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) - ); + if ((_state.mag_I - mag_I).longerThan(kMagEarthMinGauss)) { + _state.mag_I = mag_I; + resetMagEarthCov(); + } + } - } else { + if ((_state.mag_I - mag_I_before_reset).longerThan(0.f)) { ECL_INFO("resetting mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", (double)mag_I_before_reset(0), (double)mag_I_before_reset(1), (double)mag_I_before_reset(2), - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2) - ); - - if (mag_B_before_reset.longerThan(0.f) || _state.mag_B.longerThan(0.f)) { - ECL_INFO("resetting mag B [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", - (double)mag_B_before_reset(0), (double)mag_B_before_reset(1), (double)mag_B_before_reset(2), - (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) - ); - } + (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2)); + } + + if ((_state.mag_B - mag_B_before_reset).longerThan(0.f)) { + ECL_INFO("resetting mag B [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", + (double)mag_B_before_reset(0), (double)mag_B_before_reset(1), (double)mag_B_before_reset(2), + (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2)); } // record the start time for the magnetic field alignment diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index 887caf20dd15..18174caad4c0 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -99,7 +99,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima resetQuatCov(_params.mag_heading_noise); } - resetMagCov(); + resetMagEarthCov(); + resetMagBiasCov(); return false; } diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 787d1636e2ab..f148a99d9124 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -96,7 +96,8 @@ void Ekf::initialiseCovariance() resetAccelBiasCov(); #if defined(CONFIG_EKF2_MAGNETOMETER) - resetMagCov(); + resetMagEarthCov(); + resetMagBiasCov(); #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) @@ -340,11 +341,17 @@ void Ekf::resetAccelBiasCov() } #if defined(CONFIG_EKF2_MAGNETOMETER) -void Ekf::resetMagCov() +void Ekf::resetMagEarthCov() { - ECL_INFO("reset mag covariance"); + ECL_INFO("reset mag earth covariance"); P.uncorrelateCovarianceSetVariance(State::mag_I.idx, sq(_params.mag_noise)); +} + +void Ekf::resetMagBiasCov() +{ + ECL_INFO("reset mag bias covariance"); + P.uncorrelateCovarianceSetVariance(State::mag_B.idx, sq(_params.mag_noise)); } #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index edf50329bb49..dd273aa0e1c0 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -1108,7 +1108,8 @@ class Ekf final : public EstimatorInterface void resetQuatCov(const Vector3f &rot_var_ned); #if defined(CONFIG_EKF2_MAGNETOMETER) - void resetMagCov(); + void resetMagEarthCov(); + void resetMagBiasCov(); #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) From 2a9e2054427f0e722b6d20fff3d0bf43fc25dc26 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 15:30:44 -0400 Subject: [PATCH 04/31] ekf2: fuseDeclination respect mag update_all_states - when both mag_hdg/mag_3d are inactive we should be able to continue updating mag without any possible impact on other states --- .../EKF/aid_sources/magnetometer/mag_control.cpp | 4 ++-- .../EKF/aid_sources/magnetometer/mag_fusion.cpp | 15 ++++++++++++++- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 17 insertions(+), 4 deletions(-) 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 99da95e5a188..f329dc31e7ae 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -237,13 +237,13 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) && PX4_ISFINITE(_wmm_declination_rad) ) { - fuseDeclination(_wmm_declination_rad, 0.5f); + fuseDeclination(_wmm_declination_rad, 0.5f, update_all_states); } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) ) { - fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f); + fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f, update_all_states); } else { _control_status.flags.mag_dec = false; diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index 18174caad4c0..c4922322c07f 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -151,7 +151,7 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima return false; } -bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma) +bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states) { // observation variance (rad**2) const float R_DECL = sq(decl_sigma); @@ -174,6 +174,19 @@ bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma) // Calculate the Kalman gains VectorState Kfusion = P * H / innovation_variance; + if (!update_all_states) { + // zero non-mag Kalman gains if not updating all states + + // copy mag_I and mag_B Kalman gains + const Vector3f K_mag_I = Kfusion.slice(State::mag_I.idx, 0); + const Vector3f K_mag_B = Kfusion.slice(State::mag_B.idx, 0); + + // zero all Kalman gains, then restore mag + Kfusion.setZero(); + Kfusion.slice(State::mag_I.idx, 0) = K_mag_I; + Kfusion.slice(State::mag_B.idx, 0) = K_mag_B; + } + const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); _fault_status.flags.bad_mag_decl = !is_fused; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index dd273aa0e1c0..fadbd2256c01 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -773,7 +773,7 @@ class Ekf final : public EstimatorInterface // fuse magnetometer declination measurement // declination uncertainty in radians - bool fuseDeclination(float decl_measurement_rad, float decl_sigma); + bool fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states = false); #endif // CONFIG_EKF2_MAGNETOMETER From ac48b8b51d52b2e398f39eb1345c510e59c88bf3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 26 Aug 2024 10:53:17 -0400 Subject: [PATCH 05/31] ekf2: mag declination fusion always if there is no aiding --- .../aid_sources/magnetometer/mag_control.cpp | 21 ++++++++++++------- .../aid_sources/magnetometer/mag_fusion.cpp | 11 ++++------ src/modules/ekf2/EKF/ekf.h | 4 ++-- src/modules/ekf2/test/test_EKF_basics.cpp | 1 + 4 files changed, 21 insertions(+), 16 deletions(-) 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 f329dc31e7ae..13caff5ca2d6 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -205,14 +205,14 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) // if we are using 3-axis magnetometer fusion, but without external NE aiding, // then the declination must be fused as an observation to prevent long term heading drift - const bool no_ne_aiding_or_pre_takeoff = !using_ne_aiding || !_control_status.flags.in_air; - _control_status.flags.mag_dec = _control_status.flags.mag && no_ne_aiding_or_pre_takeoff; + const bool no_ne_aiding_or_not_moving = !using_ne_aiding || _control_status.flags.vehicle_at_rest; + _control_status.flags.mag_dec = _control_status.flags.mag && no_ne_aiding_or_not_moving; if (_control_status.flags.mag) { if (continuing_conditions_passing && _control_status.flags.yaw_align) { - if (checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) { + if (checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_not_moving)) { ECL_INFO("reset to %s", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = imu_sample.time_us; @@ -234,19 +234,26 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if (_control_status.flags.mag_dec) { + // observation variance (rad**2) + const float R_DECL = sq(0.5f); + if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) && PX4_ISFINITE(_wmm_declination_rad) ) { + // using declination from the world magnetic model fuseDeclination(_wmm_declination_rad, 0.5f, update_all_states); } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) ) { - - fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f, update_all_states); + // using previously saved declination + fuseDeclination(math::radians(_params.mag_declination_deg), R_DECL, update_all_states); } else { - _control_status.flags.mag_dec = false; + // if there is no aiding coming from an inertial frame we need to fuse some declination + // even if we don't know the value, it's better to fuse 0 than nothing + float declination_rad = 0.f; + fuseDeclination(declination_rad, R_DECL); } } } @@ -254,7 +261,7 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); if (is_fusion_failing) { - if (no_ne_aiding_or_pre_takeoff) { + if (no_ne_aiding_or_not_moving) { ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = imu_sample.time_us; diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index c4922322c07f..0bada1b2b60e 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -151,21 +151,18 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima return false; } -bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states) +bool Ekf::fuseDeclination(float decl_measurement_rad, float R, bool update_all_states) { - // observation variance (rad**2) - const float R_DECL = sq(decl_sigma); - VectorState H; float decl_pred; float innovation_variance; - sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, + sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R, FLT_EPSILON, &decl_pred, &innovation_variance, &H); const float innovation = wrap_pi(decl_pred - decl_measurement_rad); - if (innovation_variance < R_DECL) { + if (innovation_variance < R) { // variance calculation is badly conditioned _fault_status.flags.bad_mag_decl = true; return false; @@ -187,7 +184,7 @@ bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma, bool upd Kfusion.slice(State::mag_B.idx, 0) = K_mag_B; } - const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); + const bool is_fused = measurementUpdate(Kfusion, H, R, innovation); _fault_status.flags.bad_mag_decl = !is_fused; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index fadbd2256c01..7be3fdf92afb 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -772,8 +772,8 @@ class Ekf final : public EstimatorInterface bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement - // declination uncertainty in radians - bool fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states = false); + // R: declination observation variance (rad**2) + bool fuseDeclination(const float decl_measurement_rad, const float R, bool update_all_states = false); #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp index 0d34e676cbb9..e95443344235 100644 --- a/src/modules/ekf2/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -108,6 +108,7 @@ TEST_F(EkfBasicsTest, initialControlMode) EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_hdg); EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_3D); EXPECT_EQ(1, (int) _ekf->control_status_flags().mag); + EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_dec); EXPECT_EQ(0, (int) _ekf->control_status_flags().in_air); EXPECT_EQ(0, (int) _ekf->control_status_flags().wind); EXPECT_EQ(1, (int) _ekf->control_status_flags().baro_hgt); From 5ff4eea87091da71115de0775da107c662f65aaf Mon Sep 17 00:00:00 2001 From: dagar Date: Mon, 26 Aug 2024 17:06:27 +0000 Subject: [PATCH 06/31] [AUTO COMMIT] update change indication --- .../test/change_indication/ekf_gsf_reset.csv | 644 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 560 +++++++-------- 2 files changed, 602 insertions(+), 602 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 357bfb7370d0..f12f21d9dd01 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -67,325 +67,325 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 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.7,0.0013,-0.014,0.71,0.003,0.0048,-0.11,0.0017,0.0014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-5.7e-05,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.19,0.19,0.6,0.11,0.11,0.2,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.002,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6890000,0.7,0.0013,-0.014,0.71,0.0011,0.0051,-0.12,0.0019,0.0019,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.21,0.21,0.46,0.14,0.14,0.18,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.0014,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,0.7,0.0014,-0.014,0.71,0.0012,0.0057,-0.12,0.002,0.0024,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-5.1e-06,4.4e-06,-0.00041,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.25,0.25,0.36,0.17,0.17,0.16,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.001,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7090000,0.7,0.0013,-0.014,0.71,-0.00037,-0.00015,-0.13,0.002,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.00077,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.29,1e+02,1e+02,0.16,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00086,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7190000,0.7,0.0013,-0.014,0.71,-0.0019,-0.00023,-0.15,0.0019,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.00055,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.24,1e+02,1e+02,0.15,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00071,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7290000,0.7,0.0014,-0.014,0.71,-0.0033,-0.00022,-0.15,0.0017,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0012,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.2,51,51,0.14,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00061,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7390000,0.7,0.0014,-0.014,0.71,-0.0032,0.0011,-0.16,0.0014,0.0026,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0014,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.18,52,52,0.13,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00054,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7490000,0.71,0.0015,-0.014,0.71,-0.0047,0.0013,-0.16,0.0012,0.0027,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0022,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.15,35,35,0.12,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00048,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7590000,0.71,0.0015,-0.014,0.71,-0.0064,0.0023,-0.17,0.00071,0.0028,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.003,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.14,37,37,0.12,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00043,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7690000,0.7,0.0015,-0.014,0.71,-0.0079,0.0029,-0.16,0.00044,0.003,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0051,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,24,24,0.13,28,28,0.11,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,1,1,2 -7790000,0.71,0.0016,-0.014,0.71,-0.0091,0.0036,-0.16,-0.0004,0.0033,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0071,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,24,24,0.12,30,30,0.11,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00036,0.0025,0.0025,0.0025,0.0025,1,1,2 -7890000,0.71,0.0016,-0.014,0.71,-0.011,0.0052,-0.16,-0.0007,0.0035,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0096,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,23,23,0.11,25,25,0.1,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00033,0.0025,0.0025,0.0025,0.0025,1,1,2 -7990000,0.71,0.0016,-0.014,0.71,-0.013,0.0061,-0.16,-0.0019,0.004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,23,23,0.1,27,27,0.099,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00031,0.0025,0.0025,0.0025,0.0025,1,1,2 -8090000,0.71,0.0016,-0.014,0.71,-0.014,0.0071,-0.17,-0.0022,0.0043,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,21,21,0.1,23,23,0.097,8e-05,8e-05,2.4e-06,0.04,0.04,0.037,0.0025,0.00029,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8190000,0.71,0.0016,-0.014,0.71,-0.017,0.0084,-0.18,-0.0037,0.0051,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.013,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,21,21,0.099,26,26,0.094,8e-05,8e-05,2.4e-06,0.04,0.04,0.037,0.0025,0.00027,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8290000,0.71,0.0016,-0.014,0.71,-0.017,0.0087,-0.17,-0.0039,0.0053,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.017,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,19,19,0.097,22,22,0.091,8e-05,8e-05,2.4e-06,0.04,0.04,0.036,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8390000,0.71,0.0017,-0.014,0.71,-0.019,0.0097,-0.17,-0.0057,0.0062,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.021,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,19,19,0.097,25,25,0.091,8e-05,8e-05,2.4e-06,0.04,0.04,0.035,0.0025,0.00024,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8490000,0.71,0.0017,-0.014,0.71,-0.02,0.011,-0.17,-0.0056,0.0063,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.025,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,17,17,0.096,22,22,0.089,8e-05,8e-05,2.4e-06,0.04,0.04,0.034,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8590000,0.71,0.0017,-0.014,0.71,-0.022,0.013,-0.17,-0.0077,0.0074,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.029,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,17,17,0.095,25,25,0.088,8e-05,8e-05,2.4e-06,0.04,0.04,0.033,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8690000,0.71,0.0017,-0.014,0.71,-0.023,0.013,-0.16,-0.0074,0.0074,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.035,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.096,22,22,0.088,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.033,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8790000,0.71,0.0017,-0.014,0.71,-0.025,0.015,-0.15,-0.0099,0.0088,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.041,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.095,25,25,0.087,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.032,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8890000,0.71,0.0017,-0.014,0.71,-0.027,0.015,-0.15,-0.013,0.01,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.045,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.095,28,28,0.086,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.03,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -8990000,0.71,0.0018,-0.014,0.71,-0.027,0.015,-0.14,-0.012,0.01,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.051,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,14,14,0.096,24,24,0.087,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.029,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9090000,0.71,0.0018,-0.014,0.71,-0.03,0.016,-0.14,-0.015,0.012,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.053,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,14,14,0.095,27,27,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.028,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9190000,0.71,0.0018,-0.014,0.71,-0.029,0.016,-0.14,-0.014,0.011,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.057,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,12,12,0.094,24,24,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.027,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9290000,0.71,0.0018,-0.014,0.71,-0.031,0.017,-0.14,-0.017,0.013,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.061,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,12,12,0.093,26,26,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.025,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9390000,0.71,0.0018,-0.014,0.71,-0.03,0.017,-0.14,-0.016,0.012,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.065,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,10,10,0.093,23,23,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.024,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9490000,0.71,0.0018,-0.014,0.71,-0.032,0.018,-0.13,-0.019,0.014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.068,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,10,10,0.091,26,26,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.023,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9590000,0.71,0.0019,-0.014,0.71,-0.032,0.018,-0.13,-0.017,0.013,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.072,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.002,0.002,0.09,8.9,8.9,0.09,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.021,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9690000,0.71,0.0019,-0.014,0.71,-0.034,0.02,-0.12,-0.021,0.015,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.077,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.002,0.002,0.09,9,9,0.089,25,25,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.02,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9790000,0.71,0.0019,-0.014,0.71,-0.032,0.021,-0.11,-0.019,0.014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.082,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,7.8,7.8,0.087,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.019,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9890000,0.71,0.0019,-0.014,0.71,-0.035,0.022,-0.11,-0.022,0.016,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.085,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,7.8,7.8,0.084,24,24,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9990000,0.71,0.002,-0.014,0.71,-0.034,0.021,-0.1,-0.021,0.016,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.089,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.09,6.8,6.8,0.083,21,21,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -10090000,0.71,0.002,-0.014,0.71,-0.036,0.021,-0.096,-0.024,0.018,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.091,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.09,6.9,6.9,0.08,23,23,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10190000,0.71,0.002,-0.014,0.71,-0.035,0.022,-0.096,-0.022,0.017,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.093,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,6,6,0.078,20,20,0.084,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10290000,0.71,0.002,-0.014,0.71,-0.037,0.022,-0.084,-0.026,0.019,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.098,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,6.1,6.1,0.076,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10390000,0.71,0.002,-0.013,0.71,0.0092,-0.02,0.0096,0.00086,-0.0018,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7e-05,5.4e-05,-0.1,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.25,0.25,0.56,0.25,0.25,0.078,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10490000,0.71,0.002,-0.013,0.71,0.0077,-0.018,0.023,0.0017,-0.0036,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-0.00015,0.00012,-0.1,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.26,0.26,0.55,0.26,0.26,0.08,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10590000,0.71,0.0021,-0.014,0.71,0.0072,-0.0075,0.026,0.0018,-0.00083,-3.7e+02,-0.0015,-0.0057,-7.4e-05,-0.0004,0.00047,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.13,0.13,0.27,0.13,0.13,0.073,7.8e-05,7.8e-05,2.4e-06,0.04,0.04,0.012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10690000,0.71,0.0022,-0.014,0.71,0.0049,-0.0074,0.03,0.0024,-0.0016,-3.7e+02,-0.0015,-0.0057,-7.4e-05,-0.00043,0.00049,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0025,0.0025,0.09,0.15,0.15,0.26,0.14,0.14,0.078,7.8e-05,7.8e-05,2.4e-06,0.04,0.04,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10790000,0.71,0.0022,-0.014,0.71,0.0043,-0.0046,0.024,0.0027,-0.00079,-3.7e+02,-0.0015,-0.0057,-7.3e-05,-0.00045,0.00085,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.1,0.1,0.17,0.09,0.09,0.072,7.4e-05,7.4e-05,2.4e-06,0.039,0.039,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10890000,0.71,0.0021,-0.014,0.71,0.0028,-0.0039,0.02,0.003,-0.0012,-3.7e+02,-0.0015,-0.0057,-7.3e-05,-0.00044,0.00085,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0025,0.0025,0.09,0.12,0.12,0.16,0.097,0.097,0.075,7.4e-05,7.4e-05,2.4e-06,0.039,0.039,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -10990000,0.71,0.0022,-0.014,0.71,0.0052,0.0011,0.014,0.0046,-0.0024,-3.7e+02,-0.0015,-0.0056,-7.2e-05,-0.00019,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,0.095,0.095,0.12,0.072,0.072,0.071,6.9e-05,6.9e-05,2.4e-06,0.038,0.038,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11090000,0.71,0.0022,-0.014,0.71,0.0036,0.0031,0.019,0.0051,-0.0022,-3.7e+02,-0.0015,-0.0056,-7.2e-05,-0.00021,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.12,0.12,0.11,0.079,0.079,0.074,6.9e-05,6.9e-05,2.4e-06,0.038,0.038,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11190000,0.71,0.0021,-0.014,0.71,0.0084,0.0059,0.0076,0.0065,-0.003,-3.7e+02,-0.0015,-0.0055,-7.2e-05,0.00031,0.0029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,0.094,0.094,0.084,0.062,0.062,0.069,6.2e-05,6.2e-05,2.4e-06,0.037,0.037,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11290000,0.71,0.0022,-0.014,0.71,0.0077,0.0078,0.0073,0.0073,-0.0023,-3.7e+02,-0.0015,-0.0055,-7.2e-05,0.00031,0.0029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,0.12,0.12,0.078,0.069,0.069,0.072,6.2e-05,6.2e-05,2.4e-06,0.037,0.037,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11390000,0.71,0.0022,-0.014,0.71,0.0035,0.0071,0.0017,0.0054,-0.0021,-3.7e+02,-0.0015,-0.0056,-7.2e-05,0.00023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,0.094,0.094,0.063,0.057,0.057,0.068,5.4e-05,5.4e-05,2.4e-06,0.035,0.035,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11490000,0.71,0.0023,-0.014,0.71,0.00066,0.0096,0.0025,0.0056,-0.0013,-3.7e+02,-0.0015,-0.0056,-7.2e-05,0.00023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,0.12,0.12,0.058,0.064,0.064,0.069,5.4e-05,5.4e-05,2.4e-06,0.035,0.035,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11590000,0.71,0.0021,-0.014,0.71,-0.0032,0.0087,-0.0034,0.0043,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00053,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,0.093,0.093,0.049,0.053,0.053,0.066,4.7e-05,4.7e-05,2.4e-06,0.034,0.034,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11690000,0.71,0.0021,-0.014,0.71,-0.0063,0.012,-0.008,0.0039,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00054,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,0.11,0.11,0.046,0.062,0.062,0.066,4.7e-05,4.7e-05,2.4e-06,0.034,0.034,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -11790000,0.71,0.0022,-0.014,0.71,-0.011,0.012,-0.0098,0.0017,0.00048,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00043,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0013,0.0013,0.09,0.09,0.09,0.039,0.051,0.051,0.063,4.1e-05,4.1e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -11890000,0.71,0.0022,-0.014,0.71,-0.013,0.013,-0.011,0.00051,0.0017,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00043,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.11,0.11,0.037,0.06,0.06,0.063,4.1e-05,4.1e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -11990000,0.71,0.0022,-0.014,0.71,-0.014,0.013,-0.016,-0.00041,0.0023,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00062,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0011,0.0011,0.09,0.085,0.085,0.033,0.05,0.05,0.061,3.6e-05,3.6e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -12090000,0.71,0.0022,-0.014,0.71,-0.016,0.015,-0.022,-0.0019,0.0036,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00063,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0012,0.0012,0.09,0.1,0.1,0.031,0.059,0.059,0.061,3.6e-05,3.6e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12190000,0.71,0.0019,-0.014,0.71,-0.0095,0.013,-0.017,0.0012,0.0019,-3.7e+02,-0.0014,-0.0056,-7.7e-05,0.0016,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00099,0.00099,0.09,0.08,0.08,0.028,0.049,0.049,0.059,3.2e-05,3.2e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12290000,0.71,0.0019,-0.014,0.71,-0.012,0.014,-0.016,0.00011,0.0033,-3.7e+02,-0.0014,-0.0056,-7.7e-05,0.0016,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.001,0.001,0.09,0.095,0.095,0.028,0.058,0.058,0.059,3.2e-05,3.2e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12390000,0.71,0.0016,-0.014,0.71,-0.0067,0.011,-0.015,0.0026,0.0017,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0.0023,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00088,0.00088,0.09,0.075,0.075,0.026,0.049,0.049,0.057,2.9e-05,2.9e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12490000,0.71,0.0016,-0.014,0.71,-0.0081,0.013,-0.018,0.0019,0.0029,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0.0023,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0009,0.00089,0.09,0.088,0.088,0.026,0.058,0.058,0.057,2.9e-05,2.9e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12590000,0.71,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.003,0.0016,-3.7e+02,-0.0013,-0.0057,-7.9e-05,0.0023,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00079,0.00079,0.09,0.07,0.07,0.025,0.049,0.049,0.055,2.7e-05,2.7e-05,2.4e-06,0.032,0.032,0.0099,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12690000,0.71,0.0016,-0.014,0.71,-0.016,0.013,-0.027,-0.0046,0.0028,-3.7e+02,-0.0013,-0.0057,-7.9e-05,0.0023,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00081,0.00081,0.09,0.081,0.081,0.025,0.057,0.057,0.055,2.7e-05,2.7e-05,2.4e-06,0.032,0.032,0.0098,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12790000,0.71,0.0017,-0.014,0.71,-0.02,0.0098,-0.03,-0.0078,0.0015,-3.7e+02,-0.0013,-0.0057,-8e-05,0.0024,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00073,0.00073,0.09,0.065,0.065,0.024,0.048,0.048,0.053,2.5e-05,2.5e-05,2.4e-06,0.032,0.032,0.0097,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12890000,0.71,0.0016,-0.014,0.71,-0.021,0.0099,-0.03,-0.0099,0.0025,-3.7e+02,-0.0013,-0.0057,-8e-05,0.0024,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00074,0.00074,0.09,0.075,0.075,0.025,0.057,0.057,0.054,2.5e-05,2.5e-05,2.4e-06,0.032,0.032,0.0096,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -12990000,0.71,0.0013,-0.014,0.71,-0.0093,0.0075,-0.03,-0.0014,0.0013,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.0026,0.0017,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00068,0.00068,0.09,0.061,0.061,0.025,0.048,0.048,0.052,2.3e-05,2.3e-05,2.4e-06,0.032,0.032,0.0094,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13090000,0.71,0.0014,-0.014,0.71,-0.01,0.0079,-0.03,-0.0024,0.002,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.0026,0.0017,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00069,0.00069,0.09,0.069,0.069,0.025,0.056,0.056,0.052,2.3e-05,2.3e-05,2.4e-06,0.032,0.032,0.0094,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13190000,0.71,0.0011,-0.014,0.71,-0.001,0.0074,-0.027,0.0039,0.0012,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.0026,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00064,0.00064,0.09,0.057,0.057,0.025,0.048,0.048,0.051,2.2e-05,2.2e-05,2.4e-06,0.032,0.032,0.0091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13290000,0.71,0.0012,-0.014,0.71,-0.0013,0.0085,-0.024,0.0038,0.002,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.0026,0.0021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00066,0.00066,0.09,0.065,0.065,0.027,0.056,0.056,0.051,2.2e-05,2.2e-05,2.4e-06,0.032,0.032,0.0091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13390000,0.71,0.001,-0.014,0.71,-0.00029,0.0075,-0.02,0.0028,0.0011,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0024,0.0021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00062,0.00062,0.09,0.053,0.053,0.026,0.048,0.048,0.05,2.1e-05,2.1e-05,2.4e-06,0.032,0.032,0.0088,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13490000,0.71,0.001,-0.014,0.71,-0.0008,0.0078,-0.019,0.0028,0.0019,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0024,0.0022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00063,0.00063,0.09,0.06,0.06,0.028,0.056,0.056,0.05,2.1e-05,2.1e-05,2.4e-06,0.032,0.032,0.0087,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13590000,0.71,0.00099,-0.014,0.71,-0.00037,0.008,-0.021,0.002,0.0011,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0006,0.0006,0.09,0.05,0.05,0.028,0.048,0.048,0.05,2e-05,2e-05,2.4e-06,0.032,0.032,0.0084,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13690000,0.71,0.00098,-0.014,0.71,0.00032,0.01,-0.025,0.002,0.002,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00061,0.00061,0.09,0.057,0.057,0.029,0.055,0.055,0.05,2e-05,2e-05,2.4e-06,0.032,0.032,0.0083,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13790000,0.71,0.00089,-0.014,0.71,0.001,0.0061,-0.027,0.003,-0.00046,-3.7e+02,-0.0011,-0.0057,-8.5e-05,0.0021,0.0026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00058,0.00058,0.066,0.047,0.047,0.029,0.047,0.047,0.049,1.9e-05,1.9e-05,2.4e-06,0.032,0.032,0.0079,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13890000,0.71,0.00086,-0.014,0.71,0.0015,0.0064,-0.031,0.0032,0.00014,-3.7e+02,-0.0011,-0.0057,-8.5e-05,0.0021,0.0026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00059,0.00059,0.066,0.053,0.053,0.03,0.055,0.055,0.05,1.9e-05,1.9e-05,2.4e-06,0.032,0.032,0.0078,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13990000,0.71,0.00081,-0.014,0.71,0.0019,0.004,-0.03,0.004,-0.0018,-3.7e+02,-0.0011,-0.0058,-8.6e-05,0.0019,0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00057,0.00057,0.066,0.045,0.045,0.03,0.047,0.047,0.05,1.8e-05,1.8e-05,2.4e-06,0.031,0.031,0.0074,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -14090000,0.71,0.0008,-0.014,0.71,0.002,0.0046,-0.031,0.0042,-0.0014,-3.7e+02,-0.0011,-0.0058,-8.6e-05,0.0019,0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00058,0.00058,0.066,0.05,0.05,0.031,0.054,0.054,0.05,1.8e-05,1.8e-05,2.4e-06,0.031,0.031,0.0073,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14190000,0.71,0.0007,-0.014,0.71,0.0053,0.0039,-0.033,0.0063,-0.0014,-3.7e+02,-0.001,-0.0058,-8.7e-05,0.0014,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.043,0.043,0.03,0.047,0.047,0.05,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0069,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14290000,0.71,0.00072,-0.014,0.71,0.0061,0.0051,-0.032,0.0069,-0.00095,-3.7e+02,-0.001,-0.0058,-8.7e-05,0.0014,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00057,0.00057,0.066,0.048,0.048,0.031,0.054,0.054,0.051,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0067,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14390000,0.71,0.00064,-0.014,0.71,0.008,0.0059,-0.034,0.0083,-0.001,-3.7e+02,-0.001,-0.0058,-8.8e-05,0.001,0.0031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.041,0.041,0.031,0.047,0.047,0.05,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0063,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14490000,0.71,0.00063,-0.014,0.71,0.008,0.0076,-0.037,0.0091,-0.00035,-3.7e+02,-0.001,-0.0058,-8.8e-05,0.001,0.0031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.046,0.046,0.032,0.054,0.054,0.051,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0062,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14590000,0.71,0.00064,-0.013,0.71,0.005,0.006,-0.037,0.0057,-0.0019,-3.7e+02,-0.0011,-0.0058,-8.8e-05,0.0015,0.0037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.039,0.039,0.031,0.046,0.046,0.051,1.6e-05,1.6e-05,2.4e-06,0.031,0.031,0.0058,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14690000,0.71,0.00061,-0.013,0.71,0.0064,0.0036,-0.034,0.0063,-0.0014,-3.7e+02,-0.0011,-0.0058,-8.8e-05,0.0015,0.0038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.044,0.044,0.032,0.053,0.053,0.051,1.6e-05,1.6e-05,2.4e-06,0.031,0.031,0.0056,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14790000,0.71,0.00065,-0.013,0.71,0.0036,0.0019,-0.03,0.0035,-0.0027,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.002,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.038,0.038,0.031,0.046,0.046,0.051,1.5e-05,1.5e-05,2.4e-06,0.03,0.03,0.0053,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14890000,0.71,0.00065,-0.013,0.71,0.0052,0.0034,-0.033,0.004,-0.0024,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.002,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.042,0.042,0.031,0.053,0.053,0.052,1.5e-05,1.5e-05,2.4e-06,0.03,0.03,0.0051,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -14990000,0.71,0.00064,-0.013,0.71,0.0042,0.0029,-0.029,0.0031,-0.0021,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0022,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00053,0.066,0.037,0.037,0.03,0.046,0.046,0.051,1.4e-05,1.4e-05,2.4e-06,0.03,0.03,0.0048,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15090000,0.71,0.00057,-0.013,0.71,0.0047,0.0033,-0.032,0.0035,-0.0018,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0022,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.041,0.041,0.031,0.053,0.053,0.052,1.4e-05,1.4e-05,2.4e-06,0.03,0.03,0.0046,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15190000,0.71,0.00058,-0.013,0.71,0.0042,0.0041,-0.029,0.0028,-0.0015,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0023,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00052,0.066,0.036,0.036,0.03,0.046,0.046,0.052,1.4e-05,1.4e-05,2.4e-06,0.029,0.029,0.0043,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15290000,0.71,0.00055,-0.013,0.71,0.005,0.0049,-0.027,0.0032,-0.0011,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0023,0.0048,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.04,0.04,0.03,0.052,0.052,0.052,1.4e-05,1.4e-05,2.4e-06,0.029,0.029,0.0042,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15390000,0.71,0.00055,-0.013,0.71,0.0043,0.0048,-0.025,0.00066,-0.001,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0026,0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00052,0.00052,0.066,0.035,0.035,0.029,0.046,0.046,0.051,1.3e-05,1.3e-05,2.4e-06,0.029,0.029,0.0039,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15490000,0.71,0.00058,-0.013,0.71,0.0058,0.005,-0.025,0.0012,-0.00055,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0026,0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00053,0.066,0.039,0.039,0.029,0.052,0.052,0.053,1.3e-05,1.3e-05,2.4e-06,0.029,0.029,0.0037,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15590000,0.71,0.00059,-0.013,0.71,0.004,0.0046,-0.023,-0.0011,-0.0006,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0029,0.0054,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00051,0.00051,0.066,0.034,0.034,0.028,0.045,0.045,0.052,1.2e-05,1.2e-05,2.4e-06,0.028,0.028,0.0035,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15690000,0.71,0.0006,-0.013,0.71,0.0045,0.005,-0.024,-0.00068,-0.00011,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0029,0.0054,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00052,0.00052,0.066,0.038,0.038,0.028,0.052,0.052,0.052,1.2e-05,1.2e-05,2.4e-06,0.028,0.028,0.0033,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -15790000,0.71,0.00059,-0.013,0.71,0.0049,0.003,-0.026,-0.00071,-0.0015,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0061,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0005,0.0005,0.066,0.034,0.034,0.027,0.045,0.045,0.051,1.2e-05,1.2e-05,2.4e-06,0.027,0.027,0.0031,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -15890000,0.71,0.00055,-0.013,0.71,0.0061,0.0031,-0.024,-0.00013,-0.0012,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0029,0.0061,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00051,0.00051,0.066,0.037,0.037,0.027,0.051,0.051,0.052,1.2e-05,1.2e-05,2.4e-06,0.027,0.027,0.003,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -15990000,0.71,0.00052,-0.013,0.71,0.0059,0.0019,-0.02,-0.00031,-0.0024,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00049,0.00049,0.066,0.033,0.033,0.026,0.045,0.045,0.051,1.1e-05,1.1e-05,2.4e-06,0.026,0.026,0.0028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -16090000,0.71,0.00053,-0.013,0.71,0.0079,0.0023,-0.016,0.00036,-0.0022,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0005,0.0005,0.066,0.037,0.037,0.025,0.051,0.051,0.052,1.1e-05,1.1e-05,2.4e-06,0.026,0.026,0.0027,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16190000,0.71,0.00055,-0.013,0.71,0.0079,0.0025,-0.015,5.6e-05,-0.0019,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0034,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00048,0.00048,0.066,0.033,0.033,0.025,0.045,0.045,0.051,1e-05,1e-05,2.4e-06,0.026,0.026,0.0025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16290000,0.71,0.00057,-0.013,0.71,0.0097,0.0022,-0.016,0.00094,-0.0017,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0034,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00049,0.00049,0.066,0.036,0.036,0.024,0.051,0.051,0.052,1e-05,1e-05,2.4e-06,0.026,0.026,0.0024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16390000,0.71,0.00056,-0.013,0.71,0.0086,0.0014,-0.015,0.00051,-0.0015,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0039,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00046,0.00046,0.066,0.032,0.032,0.023,0.045,0.045,0.051,9.6e-06,9.6e-06,2.4e-06,0.025,0.025,0.0022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16490000,0.71,0.00058,-0.013,0.71,0.0081,0.0023,-0.018,0.0013,-0.0013,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0039,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00047,0.00047,0.066,0.036,0.036,0.023,0.051,0.051,0.052,9.6e-06,9.6e-06,2.4e-06,0.025,0.025,0.0021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16590000,0.71,0.00079,-0.013,0.71,0.0048,0.0041,-0.018,-0.0016,0.0014,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0057,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00045,0.00045,0.066,0.032,0.032,0.022,0.045,0.045,0.051,8.9e-06,8.9e-06,2.4e-06,0.024,0.024,0.002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16690000,0.71,0.00078,-0.013,0.71,0.0052,0.005,-0.015,-0.0011,0.0019,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0057,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00046,0.00046,0.066,0.035,0.035,0.022,0.051,0.051,0.051,8.9e-06,8.9e-06,2.4e-06,0.024,0.024,0.0019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16790000,0.71,0.0009,-0.013,0.71,0.002,0.0064,-0.014,-0.0035,0.004,-3.7e+02,-0.0012,-0.0058,-8.4e-05,0.0072,0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00043,0.00043,0.066,0.031,0.031,0.021,0.045,0.045,0.05,8.3e-06,8.3e-06,2.4e-06,0.023,0.023,0.0018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16890000,0.71,0.00092,-0.013,0.71,0.002,0.0077,-0.011,-0.0033,0.0046,-3.7e+02,-0.0012,-0.0058,-8.4e-05,0.0072,0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00044,0.00044,0.066,0.035,0.035,0.021,0.05,0.05,0.051,8.3e-06,8.3e-06,2.4e-06,0.023,0.023,0.0017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -16990000,0.71,0.00091,-0.013,0.71,0.0019,0.0054,-0.011,-0.004,0.0025,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0075,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00042,0.00042,0.066,0.031,0.031,0.02,0.044,0.044,0.05,7.7e-06,7.7e-06,2.4e-06,0.022,0.022,0.0016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17090000,0.71,0.00088,-0.013,0.71,0.003,0.0068,-0.01,-0.0038,0.0031,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0075,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00043,0.00043,0.066,0.034,0.034,0.02,0.05,0.05,0.05,7.7e-06,7.7e-06,2.4e-06,0.022,0.022,0.0016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17190000,0.71,0.00093,-0.013,0.71,0.0032,0.0065,-0.011,-0.0044,0.0013,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0078,0.0089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0004,0.0004,0.066,0.031,0.031,0.019,0.044,0.044,0.049,7.2e-06,7.2e-06,2.4e-06,0.021,0.021,0.0015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17290000,0.71,0.00091,-0.013,0.71,0.0056,0.008,-0.0067,-0.004,0.002,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0078,0.009,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00041,0.00041,0.066,0.034,0.034,0.019,0.05,0.05,0.049,7.2e-06,7.2e-06,2.4e-06,0.021,0.021,0.0014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17390000,0.71,0.00092,-0.013,0.71,0.0059,0.0068,-0.0047,-0.0034,0.00031,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00039,0.00039,0.066,0.03,0.03,0.018,0.044,0.044,0.048,6.6e-06,6.6e-06,2.4e-06,0.02,0.02,0.0013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17490000,0.71,0.00092,-0.013,0.71,0.0068,0.0068,-0.003,-0.0028,0.00098,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0004,0.0004,0.066,0.034,0.034,0.018,0.05,0.05,0.049,6.6e-06,6.6e-06,2.4e-06,0.02,0.02,0.0013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17590000,0.71,0.00087,-0.013,0.71,0.0077,0.0053,0.0025,-0.0025,-0.00054,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00037,0.00037,0.066,0.03,0.03,0.017,0.044,0.044,0.048,6.1e-06,6.1e-06,2.4e-06,0.019,0.019,0.0012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17690000,0.71,0.00084,-0.013,0.71,0.0089,0.0064,0.0019,-0.0016,1.4e-05,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00038,0.00038,0.066,0.033,0.033,0.017,0.05,0.05,0.048,6.1e-06,6.1e-06,2.4e-06,0.019,0.019,0.0012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17790000,0.71,0.00076,-0.013,0.71,0.011,0.0055,0.00056,-0.0009,-0.00017,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0071,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00036,0.00036,0.066,0.03,0.03,0.016,0.044,0.044,0.048,5.6e-06,5.6e-06,2.4e-06,0.018,0.018,0.0011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17890000,0.71,0.00077,-0.013,0.71,0.013,0.0052,0.00065,0.00028,0.0004,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0071,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00036,0.00036,0.066,0.033,0.033,0.016,0.05,0.05,0.048,5.6e-06,5.7e-06,2.4e-06,0.018,0.018,0.0011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17990000,0.71,0.00071,-0.013,0.71,0.014,0.0029,0.0019,0.00061,0.00014,-3.7e+02,-0.0013,-0.006,-8.6e-05,0.0069,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00034,0.00034,0.066,0.029,0.029,0.016,0.044,0.044,0.047,5.2e-06,5.2e-06,2.4e-06,0.017,0.017,0.00099,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -18090000,0.71,0.00072,-0.013,0.71,0.015,0.003,0.0043,0.0021,0.0004,-3.7e+02,-0.0013,-0.006,-8.6e-05,0.0069,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00035,0.00035,0.066,0.032,0.032,0.016,0.05,0.05,0.047,5.2e-06,5.2e-06,2.4e-06,0.017,0.017,0.00096,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18190000,0.71,0.00069,-0.013,0.71,0.015,0.0036,0.0056,0.0026,0.00033,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0072,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00032,0.00032,0.066,0.029,0.029,0.015,0.044,0.044,0.047,4.8e-06,4.8e-06,2.4e-06,0.016,0.016,0.00091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18290000,0.71,0.00063,-0.013,0.71,0.016,0.0033,0.0068,0.0042,0.00068,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0071,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00033,0.00033,0.066,0.032,0.032,0.015,0.05,0.05,0.046,4.8e-06,4.8e-06,2.4e-06,0.016,0.016,0.00088,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18390000,0.71,0.00066,-0.013,0.71,0.017,0.0045,0.008,0.0044,0.0006,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0074,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00031,0.00031,0.066,0.028,0.028,0.014,0.044,0.044,0.046,4.4e-06,4.4e-06,2.4e-06,0.015,0.015,0.00083,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18490000,0.71,0.00068,-0.013,0.71,0.018,0.0052,0.0076,0.0062,0.0011,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0074,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00031,0.00031,0.066,0.031,0.031,0.014,0.05,0.05,0.046,4.4e-06,4.4e-06,2.4e-06,0.015,0.015,0.00081,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18590000,0.71,0.00072,-0.013,0.71,0.017,0.0049,0.0057,0.0049,0.00079,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0083,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00029,0.00029,0.066,0.028,0.028,0.014,0.044,0.044,0.045,4e-06,4.1e-06,2.4e-06,0.014,0.014,0.00076,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18690000,0.71,0.00068,-0.013,0.71,0.017,0.0045,0.0038,0.0065,0.0013,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0083,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0003,0.0003,0.066,0.031,0.031,0.013,0.049,0.049,0.045,4e-06,4.1e-06,2.4e-06,0.014,0.014,0.00074,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18790000,0.71,0.00074,-0.013,0.71,0.015,0.0044,0.0035,0.0052,0.001,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0091,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00028,0.00028,0.066,0.027,0.027,0.013,0.044,0.044,0.045,3.7e-06,3.7e-06,2.4e-06,0.014,0.014,0.00071,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18890000,0.71,0.00077,-0.013,0.71,0.016,0.0051,0.0041,0.0068,0.0016,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0091,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00028,0.00028,0.066,0.03,0.03,0.013,0.049,0.049,0.045,3.7e-06,3.7e-06,2.4e-06,0.014,0.014,0.00068,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -18990000,0.71,0.00076,-0.013,0.71,0.017,0.0056,0.0028,0.0077,0.0012,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.009,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00027,0.00027,0.066,0.027,0.027,0.012,0.044,0.044,0.044,3.4e-06,3.4e-06,2.4e-06,0.013,0.013,0.00065,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19090000,0.71,0.00075,-0.013,0.71,0.018,0.0065,0.0058,0.0095,0.0019,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.009,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00027,0.00027,0.066,0.029,0.029,0.012,0.049,0.049,0.044,3.4e-06,3.4e-06,2.4e-06,0.013,0.013,0.00063,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19190000,0.71,0.00077,-0.012,0.71,0.018,0.006,0.0059,0.0099,0.0015,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0089,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00025,0.00025,0.066,0.026,0.026,0.012,0.044,0.044,0.044,3.1e-06,3.2e-06,2.4e-06,0.012,0.012,0.0006,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19290000,0.71,0.00079,-0.012,0.71,0.018,0.0055,0.0086,0.012,0.0021,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0089,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00026,0.00026,0.066,0.029,0.029,0.012,0.049,0.049,0.044,3.1e-06,3.2e-06,2.4e-06,0.012,0.012,0.00059,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19390000,0.71,0.00084,-0.012,0.71,0.016,0.0042,0.012,0.0095,0.0016,-3.7e+02,-0.0013,-0.006,-8.4e-05,0.0098,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00024,0.00024,0.066,0.026,0.026,0.012,0.043,0.043,0.043,2.9e-06,2.9e-06,2.4e-06,0.012,0.012,0.00056,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19490000,0.71,0.00086,-0.012,0.71,0.015,0.0037,0.0088,0.011,0.002,-3.7e+02,-0.0013,-0.006,-8.4e-05,0.0098,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00025,0.00025,0.066,0.028,0.028,0.011,0.049,0.049,0.043,2.9e-06,2.9e-06,2.4e-06,0.012,0.012,0.00055,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19590000,0.71,0.00094,-0.012,0.71,0.013,0.0023,0.0081,0.009,0.0016,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.01,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00023,0.00023,0.066,0.025,0.025,0.011,0.043,0.043,0.042,2.7e-06,2.7e-06,2.4e-06,0.011,0.011,0.00052,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19690000,0.71,0.00094,-0.012,0.71,0.013,0.00031,0.0096,0.01,0.0017,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.01,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00023,0.00023,0.066,0.028,0.028,0.011,0.049,0.049,0.042,2.7e-06,2.7e-06,2.4e-06,0.011,0.011,0.00051,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -19790000,0.71,0.001,-0.012,0.71,0.011,-0.00093,0.01,0.0084,0.0014,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.011,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00022,0.00022,0.066,0.025,0.025,0.011,0.043,0.043,0.042,2.5e-06,2.5e-06,2.4e-06,0.011,0.011,0.00049,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -19890000,0.71,0.00098,-0.012,0.71,0.0097,-0.001,0.011,0.0094,0.0013,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.011,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00022,0.00022,0.066,0.027,0.027,0.011,0.049,0.049,0.042,2.5e-06,2.5e-06,2.4e-06,0.011,0.011,0.00048,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -19990000,0.71,0.00098,-0.012,0.71,0.007,-0.0021,0.014,0.0077,0.00099,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00021,0.00021,0.066,0.024,0.024,0.01,0.043,0.043,0.041,2.3e-06,2.3e-06,2.4e-06,0.01,0.01,0.00046,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -20090000,0.71,0.00098,-0.012,0.71,0.0069,-0.0039,0.014,0.0084,0.00071,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00021,0.00021,0.066,0.026,0.026,0.01,0.048,0.048,0.042,2.3e-06,2.3e-06,2.4e-06,0.01,0.01,0.00045,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20190000,0.71,0.0011,-0.012,0.71,0.0044,-0.0049,0.017,0.0059,0.0006,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0002,0.0002,0.066,0.024,0.024,0.01,0.043,0.043,0.041,2.1e-06,2.1e-06,2.4e-06,0.0097,0.0097,0.00043,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20290000,0.71,0.0011,-0.012,0.71,0.0034,-0.0063,0.015,0.0063,3.9e-05,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0002,0.0002,0.066,0.026,0.026,0.0099,0.048,0.048,0.041,2.1e-06,2.1e-06,2.4e-06,0.0097,0.0097,0.00042,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20390000,0.71,0.0011,-0.012,0.71,0.00074,-0.0073,0.017,0.0041,6.5e-05,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00019,0.00019,0.066,0.023,0.023,0.0097,0.043,0.043,0.041,1.9e-06,1.9e-06,2.4e-06,0.0092,0.0093,0.00041,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20490000,0.71,0.0011,-0.012,0.71,0.00044,-0.0078,0.016,0.0041,-0.00069,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00019,0.00019,0.066,0.025,0.025,0.0096,0.048,0.048,0.041,1.9e-06,1.9e-06,2.4e-06,0.0092,0.0093,0.0004,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20590000,0.71,0.0012,-0.012,0.71,0.0005,-0.0081,0.013,0.0035,-0.00055,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.023,0.023,0.0093,0.043,0.043,0.04,1.8e-06,1.8e-06,2.4e-06,0.0088,0.0089,0.00038,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20690000,0.71,0.0012,-0.012,0.71,0.00066,-0.0094,0.015,0.0035,-0.0014,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.025,0.025,0.0093,0.048,0.048,0.04,1.8e-06,1.8e-06,2.4e-06,0.0088,0.0089,0.00037,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20790000,0.71,0.0012,-0.012,0.71,-0.00073,-0.0088,0.015,0.0029,-0.0011,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.022,0.022,0.0091,0.043,0.043,0.04,1.7e-06,1.7e-06,2.4e-06,0.0085,0.0085,0.00036,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20890000,0.71,0.0012,-0.012,0.71,-0.001,-0.011,0.014,0.0028,-0.0021,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.024,0.024,0.009,0.048,0.048,0.04,1.7e-06,1.7e-06,2.5e-06,0.0085,0.0085,0.00035,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -20990000,0.71,0.0012,-0.012,0.71,-0.0015,-0.012,0.015,0.0041,-0.0018,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.022,0.022,0.0088,0.042,0.042,0.039,1.6e-06,1.6e-06,2.5e-06,0.0081,0.0082,0.00034,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -21090000,0.71,0.0012,-0.012,0.71,-0.0016,-0.014,0.015,0.004,-0.0031,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.024,0.024,0.0088,0.047,0.047,0.039,1.6e-06,1.6e-06,2.5e-06,0.0081,0.0082,0.00033,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -21190000,0.71,0.0012,-0.012,0.71,-0.001,-0.013,0.014,0.0051,-0.0025,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00016,0.00016,0.066,0.021,0.021,0.0086,0.042,0.042,0.039,1.5e-06,1.5e-06,2.5e-06,0.0078,0.0078,0.00032,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -21290000,0.71,0.0012,-0.012,0.71,-0.0015,-0.016,0.016,0.005,-0.004,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00016,0.00016,0.066,0.023,0.023,0.0085,0.047,0.047,0.039,1.5e-06,1.5e-06,2.5e-06,0.0078,0.0078,0.00032,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21390000,0.71,0.0013,-0.012,0.71,-0.0025,-0.015,0.016,0.0042,-0.0023,-3.7e+02,-0.0014,-0.0059,-8.2e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.021,0.021,0.0084,0.042,0.042,0.039,1.4e-06,1.4e-06,2.5e-06,0.0075,0.0076,0.00031,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21490000,0.71,0.0013,-0.012,0.71,-0.0029,-0.016,0.015,0.0039,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.2e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.023,0.023,0.0083,0.047,0.047,0.038,1.4e-06,1.4e-06,2.5e-06,0.0075,0.0076,0.0003,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21590000,0.71,0.0013,-0.012,0.71,-0.0037,-0.014,0.015,0.0033,-0.0021,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.02,0.02,0.0081,0.042,0.042,0.038,1.3e-06,1.3e-06,2.5e-06,0.0073,0.0073,0.00029,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21690000,0.71,0.0013,-0.012,0.71,-0.0035,-0.015,0.017,0.0029,-0.0035,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.022,0.022,0.0081,0.047,0.047,0.038,1.3e-06,1.3e-06,2.5e-06,0.0073,0.0073,0.00029,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 -21790000,0.71,0.0012,-0.013,0.71,-0.0043,-0.0098,0.015,0.0014,0.00015,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.015,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00014,0.00014,0.066,0.02,0.02,0.008,0.042,0.042,0.038,1.2e-06,1.2e-06,2.5e-06,0.007,0.007,0.00028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 -21890000,0.71,0.0012,-0.012,0.71,-0.0042,-0.01,0.016,0.00098,-0.00084,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.015,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00014,0.00014,0.066,0.022,0.022,0.0079,0.047,0.047,0.038,1.2e-06,1.2e-06,2.5e-06,0.007,0.007,0.00028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 -21990000,0.71,0.0013,-0.013,0.71,-0.0048,-0.0077,0.016,-0.00016,0.0023,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00014,0.00014,0.066,0.02,0.02,0.0078,0.042,0.042,0.038,1.1e-06,1.1e-06,2.5e-06,0.0068,0.0068,0.00027,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22090000,0.71,0.0013,-0.013,0.71,-0.0051,-0.0068,0.015,-0.00065,0.0016,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00014,0.00014,0.066,0.021,0.021,0.0078,0.046,0.046,0.037,1.1e-06,1.1e-06,2.5e-06,0.0068,0.0068,0.00026,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22190000,0.71,0.0012,-0.013,0.71,-0.0051,-0.006,0.015,-0.00055,0.0014,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.019,0.019,0.0076,0.042,0.042,0.037,1e-06,1e-06,2.5e-06,0.0066,0.0066,0.00026,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22290000,0.71,0.0013,-0.013,0.71,-0.0064,-0.0067,0.015,-0.0011,0.00073,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.021,0.021,0.0076,0.046,0.046,0.037,1e-06,1e-06,2.5e-06,0.0066,0.0066,0.00025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22390000,0.71,0.0013,-0.013,0.71,-0.0071,-0.0063,0.017,-0.00099,0.00058,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.019,0.019,0.0075,0.041,0.041,0.037,9.9e-07,9.9e-07,2.5e-06,0.0064,0.0064,0.00025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22490000,0.71,0.0013,-0.013,0.71,-0.0077,-0.0061,0.018,-0.0017,-5.8e-05,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.02,0.02,0.0074,0.046,0.046,0.037,9.9e-07,9.9e-07,2.5e-06,0.0064,0.0064,0.00024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22590000,0.71,0.0012,-0.013,0.71,-0.0076,-0.0058,0.017,-0.0022,0.00086,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.018,0.019,0.0073,0.041,0.041,0.036,9.3e-07,9.3e-07,2.5e-06,0.0062,0.0062,0.00024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22690000,0.71,0.0013,-0.013,0.71,-0.0087,-0.0055,0.018,-0.0031,0.0003,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.02,0.02,0.0073,0.046,0.046,0.036,9.3e-07,9.3e-07,2.5e-06,0.0062,0.0062,0.00023,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22790000,0.71,0.0012,-0.013,0.71,-0.0094,-0.0044,0.019,-0.0044,0.00027,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.018,0.018,0.0072,0.041,0.041,0.036,8.8e-07,8.8e-07,2.5e-06,0.0061,0.0061,0.00023,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22890000,0.71,0.0012,-0.013,0.71,-0.011,-0.004,0.021,-0.0054,-0.00015,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.02,0.02,0.0072,0.046,0.046,0.036,8.8e-07,8.8e-07,2.5e-06,0.0061,0.0061,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22990000,0.71,0.0012,-0.013,0.71,-0.011,-0.0045,0.022,-0.0063,-0.00017,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0099,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.018,0.0071,0.041,0.041,0.036,8.4e-07,8.3e-07,2.5e-06,0.0059,0.0059,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23090000,0.71,0.0012,-0.012,0.71,-0.012,-0.0045,0.022,-0.0075,-0.00061,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0099,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.019,0.019,0.007,0.045,0.045,0.036,8.4e-07,8.4e-07,2.5e-06,0.0059,0.0059,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23190000,0.71,0.0013,-0.012,0.71,-0.013,-0.0055,0.024,-0.011,-0.00059,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.018,0.0069,0.041,0.041,0.035,8e-07,7.9e-07,2.5e-06,0.0058,0.0058,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23290000,0.71,0.0012,-0.012,0.71,-0.014,-0.0067,0.024,-0.012,-0.0012,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.019,0.019,0.0069,0.045,0.045,0.036,8e-07,7.9e-07,2.5e-06,0.0058,0.0058,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23390000,0.71,0.0013,-0.012,0.71,-0.015,-0.0071,0.022,-0.015,-0.0011,-3.7e+02,-0.0014,-0.0059,-8e-05,0.016,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.017,0.017,0.0068,0.041,0.041,0.035,7.6e-07,7.5e-07,2.5e-06,0.0056,0.0056,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23490000,0.71,0.0037,-0.01,0.71,-0.022,-0.0078,-0.012,-0.017,-0.0019,-3.7e+02,-0.0014,-0.0059,-8e-05,0.016,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.019,0.019,0.0068,0.045,0.045,0.035,7.6e-07,7.5e-07,2.5e-06,0.0056,0.0056,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23590000,0.71,0.0089,-0.0022,0.71,-0.032,-0.0067,-0.043,-0.016,-0.00069,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.017,0.017,0.0067,0.04,0.04,0.035,7.2e-07,7.2e-07,2.5e-06,0.0055,0.0055,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23690000,0.71,0.0085,0.0036,0.71,-0.063,-0.015,-0.094,-0.02,-0.0017,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.019,0.0067,0.045,0.045,0.035,7.2e-07,7.2e-07,2.5e-06,0.0055,0.0055,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23790000,0.71,0.0055,0.00025,0.71,-0.087,-0.026,-0.15,-0.02,-0.0012,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0086,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.017,0.017,0.0066,0.04,0.04,0.035,6.9e-07,6.9e-07,2.5e-06,0.0054,0.0054,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23890000,0.71,0.0029,-0.0058,0.71,-0.1,-0.035,-0.2,-0.029,-0.0043,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0086,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.018,0.019,0.0066,0.045,0.045,0.035,6.9e-07,6.9e-07,2.5e-06,0.0054,0.0054,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23990000,0.71,0.0015,-0.01,0.71,-0.1,-0.039,-0.25,-0.033,-0.0076,-3.7e+02,-0.0014,-0.0059,-8e-05,0.014,0.0081,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,9.9e-05,0.066,0.017,0.018,0.0066,0.04,0.04,0.035,6.6e-07,6.5e-07,2.5e-06,0.0053,0.0053,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24090000,0.71,0.0028,-0.0091,0.71,-0.11,-0.039,-0.3,-0.044,-0.011,-3.7e+02,-0.0014,-0.0059,-8e-05,0.014,0.0081,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.018,0.019,0.0065,0.044,0.045,0.035,6.6e-07,6.6e-07,2.5e-06,0.0053,0.0053,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24190000,0.71,0.0038,-0.0069,0.71,-0.11,-0.04,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.013,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,9.6e-05,0.066,0.017,0.017,0.0065,0.04,0.04,0.034,6.3e-07,6.3e-07,2.5e-06,0.0052,0.0052,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24290000,0.71,0.0043,-0.006,0.71,-0.12,-0.044,-0.41,-0.057,-0.018,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.013,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.8e-05,9.8e-05,0.066,0.018,0.019,0.0065,0.044,0.044,0.034,6.3e-07,6.3e-07,2.5e-06,0.0052,0.0052,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24390000,0.7,0.0043,-0.0062,0.71,-0.13,-0.051,-0.46,-0.063,-0.029,-3.7e+02,-0.0013,-0.0059,-8.1e-05,0.012,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,9.4e-05,0.066,0.016,0.017,0.0064,0.04,0.04,0.034,6e-07,6e-07,2.5e-06,0.0051,0.0051,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24490000,0.7,0.0052,-0.0021,0.71,-0.14,-0.056,-0.51,-0.076,-0.035,-3.7e+02,-0.0013,-0.0059,-8.1e-05,0.012,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.5e-05,9.5e-05,0.066,0.018,0.019,0.0064,0.044,0.044,0.034,6e-07,6e-07,2.5e-06,0.0051,0.0051,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24590000,0.7,0.0056,0.0016,0.71,-0.16,-0.068,-0.56,-0.08,-0.044,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.011,0.0075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,9.2e-05,0.065,0.016,0.017,0.0063,0.04,0.04,0.034,5.8e-07,5.8e-07,2.5e-06,0.005,0.005,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24690000,0.7,0.0057,0.0026,0.71,-0.18,-0.081,-0.64,-0.097,-0.052,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.011,0.0075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,9.3e-05,0.065,0.018,0.019,0.0063,0.044,0.044,0.034,5.8e-07,5.8e-07,2.5e-06,0.005,0.005,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24790000,0.7,0.0053,0.0012,0.71,-0.2,-0.094,-0.73,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.01,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,8.9e-05,0.065,0.016,0.018,0.0062,0.04,0.04,0.034,5.6e-07,5.6e-07,2.5e-06,0.005,0.0049,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24890000,0.7,0.0071,0.0029,0.71,-0.22,-0.11,-0.75,-0.13,-0.072,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.01,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,9e-05,0.065,0.018,0.02,0.0062,0.044,0.044,0.034,5.6e-07,5.6e-07,2.5e-06,0.005,0.0049,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24990000,0.71,0.0088,0.0046,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.0091,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,8.7e-05,0.064,0.016,0.018,0.0062,0.04,0.04,0.034,5.4e-07,5.4e-07,2.5e-06,0.0049,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25090000,0.71,0.0091,0.004,0.71,-0.27,-0.12,-0.86,-0.15,-0.092,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.0091,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.9e-05,8.8e-05,0.064,0.018,0.02,0.0062,0.044,0.044,0.034,5.4e-07,5.4e-07,2.5e-06,0.0049,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25190000,0.7,0.0086,0.0026,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,-8.3e-05,0.0082,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,8.5e-05,0.063,0.016,0.019,0.0061,0.04,0.04,0.033,5.2e-07,5.2e-07,2.5e-06,0.0048,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,-8.3e-05,0.0082,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,8.6e-05,0.063,0.017,0.021,0.0061,0.044,0.044,0.033,5.2e-07,5.2e-07,2.5e-06,0.0048,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25390000,0.7,0.012,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,-8.4e-05,0.0066,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,8.3e-05,0.062,0.016,0.02,0.0061,0.039,0.04,0.033,5e-07,5e-07,2.5e-06,0.0048,0.0047,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,-8.4e-05,0.0066,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,8.4e-05,0.062,0.018,0.023,0.0061,0.044,0.045,0.033,5e-07,5.1e-07,2.5e-06,0.0048,0.0047,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0053,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,8.1e-05,0.06,0.016,0.022,0.006,0.039,0.04,0.033,4.9e-07,4.9e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0053,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,8.2e-05,0.06,0.018,0.025,0.006,0.043,0.045,0.033,4.9e-07,4.9e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,-8.6e-05,0.003,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.4e-05,8e-05,0.058,0.017,0.024,0.006,0.039,0.04,0.033,4.7e-07,4.8e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25890000,0.7,0.018,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,-8.6e-05,0.003,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,8e-05,0.058,0.018,0.029,0.006,0.043,0.045,0.033,4.7e-07,4.8e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25990000,0.7,0.017,0.026,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0011,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.8e-05,0.055,0.017,0.028,0.0059,0.039,0.041,0.033,4.6e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26090000,0.7,0.021,0.036,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0011,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.9e-05,0.055,0.019,0.032,0.0059,0.043,0.046,0.033,4.6e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0021,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.6e-05,0.051,0.017,0.031,0.0059,0.039,0.041,0.032,4.5e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0021,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,7.7e-05,0.051,0.019,0.037,0.0059,0.043,0.046,0.033,4.5e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26390000,0.7,0.023,0.044,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0043,0.0016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,7.5e-05,0.046,0.018,0.035,0.0058,0.039,0.042,0.032,4.4e-07,4.6e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26490000,0.7,0.031,0.06,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0043,0.0016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,7.6e-05,0.046,0.02,0.042,0.0058,0.043,0.047,0.032,4.4e-07,4.6e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26590000,0.7,0.037,0.076,0.71,-1.1,-0.59,-1.3,-0.82,-0.66,-3.7e+02,-0.00096,-0.0059,-8.9e-05,-0.0082,-0.00089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,7.4e-05,0.041,0.019,0.041,0.0058,0.039,0.042,0.032,4.3e-07,4.6e-07,2.5e-06,0.0046,0.0044,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26690000,0.7,0.038,0.079,0.71,-1.3,-0.65,-1.3,-0.95,-0.73,-3.7e+02,-0.00096,-0.0059,-8.9e-05,-0.0082,-0.00089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,7.5e-05,0.041,0.021,0.051,0.0058,0.043,0.049,0.032,4.3e-07,4.6e-07,2.5e-06,0.0046,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26790000,0.7,0.036,0.073,0.71,-1.4,-0.74,-1.3,-1,-0.85,-3.7e+02,-0.00092,-0.0059,-9.5e-05,-0.011,-0.00024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.9e-05,7.3e-05,0.034,0.02,0.048,0.0058,0.039,0.043,0.032,4.2e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26890000,0.7,0.045,0.095,0.71,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.0059,-9.5e-05,-0.011,-0.00024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7.3e-05,0.034,0.022,0.058,0.0058,0.044,0.05,0.032,4.2e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26990000,0.7,0.05,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.0059,-9.8e-05,-0.017,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7.2e-05,0.028,0.021,0.054,0.0057,0.039,0.044,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27090000,0.7,0.051,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.0059,-9.8e-05,-0.017,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7.2e-05,0.028,0.024,0.069,0.0058,0.044,0.051,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27190000,0.71,0.049,0.11,0.69,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00077,-0.0059,-8.2e-05,-0.019,-0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7.2e-05,0.023,0.024,0.065,0.0057,0.046,0.053,0.032,4.1e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27290000,0.71,0.043,0.095,0.69,-2.3,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00077,-0.0059,-8.2e-05,-0.019,-0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,7.3e-05,0.023,0.026,0.076,0.0058,0.051,0.062,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27390000,0.72,0.037,0.079,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.0007,-0.0059,-7.4e-05,-0.022,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,7.2e-05,0.018,0.024,0.064,0.0057,0.053,0.062,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27490000,0.72,0.031,0.064,0.69,-2.5,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.0007,-0.0059,-7.4e-05,-0.022,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7.3e-05,0.018,0.026,0.069,0.0057,0.059,0.072,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27590000,0.73,0.026,0.051,0.69,-2.5,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.0007,-0.0059,-6.5e-05,-0.022,-0.0056,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7.2e-05,0.015,0.024,0.056,0.0057,0.061,0.072,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27690000,0.73,0.026,0.05,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.0007,-0.0059,-6.5e-05,-0.022,-0.0056,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,7.3e-05,0.015,0.025,0.057,0.0057,0.067,0.082,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27790000,0.73,0.026,0.051,0.68,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00069,-0.006,-6e-05,-0.023,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.5e-05,7.2e-05,0.012,0.023,0.047,0.0057,0.069,0.081,0.032,3.9e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27890000,0.73,0.025,0.049,0.68,-2.7,-1.1,-1.2,-3.3,-1.9,-3.7e+02,-0.00069,-0.006,-6e-05,-0.023,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.6e-05,7.3e-05,0.012,0.024,0.049,0.0057,0.076,0.092,0.032,3.9e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27990000,0.73,0.024,0.046,0.68,-2.7,-1.1,-1.2,-3.6,-2,-3.7e+02,-0.00072,-0.006,-5.6e-05,-0.022,-0.0039,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,7.2e-05,0.011,0.023,0.042,0.0057,0.078,0.091,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28090000,0.73,0.03,0.059,0.68,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00072,-0.006,-5.6e-05,-0.022,-0.0039,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.8e-05,7.3e-05,0.011,0.024,0.043,0.0057,0.085,0.1,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28190000,0.73,0.036,0.072,0.68,-2.8,-1.2,-0.94,-4.2,-2.2,-3.7e+02,-0.00074,-0.006,-5.4e-05,-0.022,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,7.2e-05,0.01,0.022,0.038,0.0057,0.087,0.1,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28290000,0.73,0.028,0.055,0.68,-2.8,-1.2,-0.08,-4.5,-2.3,-3.7e+02,-0.00074,-0.006,-5.4e-05,-0.022,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.01,0.022,0.038,0.0057,0.094,0.11,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28390000,0.73,0.011,0.024,0.68,-2.8,-1.2,0.78,-4.8,-2.5,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.3e-05,0.01,0.023,0.038,0.0057,0.1,0.12,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28490000,0.73,0.001,0.0062,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.4e-05,0.01,0.023,0.038,0.0057,0.11,0.13,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28590000,0.73,-0.00091,0.0027,0.68,-2.7,-1.2,0.97,-5.3,-2.7,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.5e-05,0.01,0.024,0.036,0.0057,0.12,0.15,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28690000,0.73,-0.0017,0.0018,0.68,-2.6,-1.2,0.98,-5.6,-2.8,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.6e-05,0.01,0.025,0.035,0.0057,0.13,0.16,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28790000,0.73,-0.0017,0.0017,0.68,-2.6,-1.1,0.98,-5.9,-2.9,-3.7e+02,-0.00078,-0.006,-5.2e-05,-0.02,-0.0014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0096,0.024,0.03,0.0057,0.13,0.16,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28890000,0.73,-0.0018,0.0019,0.68,-2.5,-1.1,0.97,-6.2,-3,-3.7e+02,-0.00078,-0.006,-5.2e-05,-0.02,-0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0096,0.025,0.029,0.0057,0.14,0.17,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28990000,0.74,-0.0013,0.0026,0.68,-2.5,-1.1,0.97,-6.5,-3.1,-3.7e+02,-0.00086,-0.006,-5.2e-05,-0.017,0.00024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0094,0.024,0.026,0.0057,0.14,0.17,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29090000,0.74,-0.0011,0.003,0.68,-2.4,-1.1,0.96,-6.7,-3.2,-3.7e+02,-0.00086,-0.006,-5.2e-05,-0.017,0.00044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0094,0.025,0.027,0.0057,0.15,0.18,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29190000,0.74,-0.00074,0.0034,0.68,-2.4,-1.1,0.95,-7,-3.3,-3.7e+02,-0.0009,-0.006,-5.4e-05,-0.015,0.0014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.024,0.025,0.0057,0.15,0.18,0.032,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29290000,0.74,-0.00041,0.0042,0.68,-2.3,-1.1,0.98,-7.3,-3.4,-3.7e+02,-0.0009,-0.006,-5.4e-05,-0.015,0.0017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0093,0.025,0.025,0.0057,0.16,0.19,0.032,3.7e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29390000,0.74,0.00042,0.0058,0.67,-2.3,-1.1,0.99,-7.6,-3.6,-3.7e+02,-0.00096,-0.006,-5.7e-05,-0.012,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.024,0.024,0.0056,0.16,0.19,0.031,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29490000,0.74,0.00093,0.0069,0.67,-2.2,-1.1,0.99,-7.8,-3.7,-3.7e+02,-0.00096,-0.006,-5.7e-05,-0.012,0.0032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0093,0.025,0.025,0.0057,0.17,0.2,0.032,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29590000,0.74,0.0015,0.0079,0.67,-2.2,-1.1,0.98,-8.1,-3.8,-3.7e+02,-0.001,-0.006,-6.4e-05,-0.01,0.0036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.024,0.024,0.0056,0.17,0.2,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29690000,0.74,0.0018,0.0085,0.67,-2.2,-1.1,0.98,-8.3,-3.9,-3.7e+02,-0.00099,-0.006,-6.4e-05,-0.011,0.0038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.026,0.026,0.0056,0.18,0.21,0.031,3.6e-07,4.5e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29790000,0.74,0.0023,0.009,0.67,-2.1,-1.1,0.96,-8.6,-4,-3.7e+02,-0.001,-0.006,-7.3e-05,-0.0081,0.0042,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0092,0.024,0.025,0.0056,0.18,0.21,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29890000,0.74,0.0023,0.0091,0.67,-2.1,-1.1,0.95,-8.8,-4.1,-3.7e+02,-0.001,-0.006,-7.3e-05,-0.0083,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.026,0.027,0.0056,0.19,0.22,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29990000,0.74,0.0026,0.0091,0.67,-2.1,-1.1,0.94,-9,-4.2,-3.7e+02,-0.0011,-0.006,-8.5e-05,-0.0066,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0092,0.025,0.026,0.0056,0.19,0.22,0.031,3.5e-07,4.3e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30090000,0.74,0.0025,0.009,0.67,-2.1,-1.1,0.92,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,-8.5e-05,-0.0068,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.026,0.028,0.0056,0.2,0.23,0.031,3.5e-07,4.3e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30190000,0.74,0.0028,0.0088,0.67,-2,-1.1,0.91,-9.5,-4.4,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0045,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0091,0.025,0.027,0.0056,0.2,0.23,0.031,3.5e-07,4.2e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30290000,0.74,0.0027,0.0086,0.67,-2,-1.1,0.9,-9.7,-4.5,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0046,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0091,0.026,0.03,0.0056,0.21,0.24,0.031,3.5e-07,4.2e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30390000,0.74,0.0028,0.0083,0.67,-2,-1.1,0.89,-9.9,-4.6,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0031,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.2e-05,0.009,0.025,0.029,0.0055,0.21,0.24,0.031,3.4e-07,4.1e-07,2.5e-06,0.0042,0.0041,9.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30490000,0.74,0.0026,0.008,0.67,-1.9,-1.1,0.87,-10,-4.7,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0032,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.009,0.026,0.031,0.0056,0.22,0.25,0.031,3.4e-07,4.1e-07,2.5e-06,0.0042,0.0041,9.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30590000,0.74,0.0027,0.0075,0.68,-1.9,-1.1,0.83,-10,-4.8,-3.7e+02,-0.0012,-0.0059,-0.00012,-0.0012,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0089,0.025,0.03,0.0055,0.22,0.25,0.031,3.4e-07,3.9e-07,2.5e-06,0.0042,0.004,9.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30690000,0.74,0.0025,0.0072,0.68,-1.9,-1.1,0.83,-11,-4.9,-3.7e+02,-0.0012,-0.0059,-0.00012,-0.0014,0.0049,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0089,0.027,0.032,0.0055,0.23,0.26,0.031,3.4e-07,3.9e-07,2.5e-06,0.0042,0.004,9.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30790000,0.74,0.0026,0.0067,0.68,-1.9,-1,0.82,-11,-4.9,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00039,0.0042,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.1e-05,0.0087,0.025,0.031,0.0055,0.23,0.26,0.031,3.3e-07,3.8e-07,2.5e-06,0.0042,0.004,9.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30890000,0.74,0.0024,0.0062,0.68,-1.8,-1,0.81,-11,-5,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00024,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0087,0.027,0.033,0.0055,0.24,0.27,0.031,3.3e-07,3.8e-07,2.5e-06,0.0042,0.004,9.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30990000,0.74,0.0026,0.0056,0.68,-1.8,-1,0.8,-11,-5.1,-3.7e+02,-0.0012,-0.0059,-0.00015,0.0024,0.0041,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,7.1e-05,0.0085,0.025,0.032,0.0055,0.24,0.27,0.031,3.3e-07,3.7e-07,2.5e-06,0.0041,0.004,9.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31090000,0.74,0.0023,0.0051,0.68,-1.8,-1,0.79,-11,-5.2,-3.7e+02,-0.0012,-0.0059,-0.00015,0.0022,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0085,0.027,0.034,0.0055,0.25,0.28,0.031,3.3e-07,3.7e-07,2.5e-06,0.0041,0.0039,9.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31190000,0.73,0.0023,0.0046,0.68,-1.8,-1,0.78,-12,-5.3,-3.7e+02,-0.0013,-0.0059,-0.00016,0.0034,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.6e-05,7.1e-05,0.0083,0.025,0.032,0.0055,0.25,0.28,0.031,3.2e-07,3.6e-07,2.5e-06,0.0041,0.0039,9.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31290000,0.73,0.0021,0.0041,0.68,-1.8,-1,0.78,-12,-5.4,-3.7e+02,-0.0013,-0.0059,-0.00016,0.0032,0.005,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,7.1e-05,0.0083,0.027,0.035,0.0055,0.26,0.29,0.031,3.2e-07,3.6e-07,2.5e-06,0.0041,0.0039,9.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31390000,0.73,0.0021,0.0034,0.68,-1.7,-1,0.78,-12,-5.5,-3.7e+02,-0.0013,-0.0058,-0.00018,0.0049,0.0051,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7e-05,0.008,0.026,0.033,0.0054,0.25,0.29,0.031,3.1e-07,3.4e-07,2.5e-06,0.0041,0.0039,9.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31490000,0.73,0.0018,0.0028,0.68,-1.7,-1,0.78,-12,-5.6,-3.7e+02,-0.0013,-0.0058,-0.00018,0.0047,0.0055,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,7.1e-05,0.008,0.027,0.035,0.0055,0.27,0.3,0.031,3.2e-07,3.5e-07,2.5e-06,0.0041,0.0039,9.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31590000,0.73,0.0019,0.0022,0.68,-1.7,-0.98,0.77,-12,-5.7,-3.7e+02,-0.0013,-0.0058,-0.00019,0.0062,0.0052,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7e-05,0.0078,0.026,0.033,0.0054,0.26,0.3,0.031,3.1e-07,3.3e-07,2.5e-06,0.004,0.0038,9.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31690000,0.73,0.0016,0.0015,0.68,-1.7,-0.98,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,-0.00019,0.006,0.0056,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7e-05,0.0078,0.027,0.035,0.0054,0.28,0.31,0.031,3.1e-07,3.3e-07,2.5e-06,0.004,0.0038,9.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31790000,0.73,0.0015,0.00072,0.68,-1.6,-0.96,0.78,-13,-5.9,-3.7e+02,-0.0013,-0.0058,-0.0002,0.0077,0.0056,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,6.9e-05,0.0075,0.026,0.033,0.0054,0.27,0.31,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,9.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31890000,0.73,0.0012,-7.5e-06,0.68,-1.6,-0.96,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,-0.0002,0.0075,0.0061,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,7e-05,0.0075,0.027,0.035,0.0054,0.29,0.32,0.031,3.1e-07,3.2e-07,2.5e-06,0.004,0.0038,9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31990000,0.73,0.0012,-0.00065,0.68,-1.6,-0.94,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,-0.00022,0.0085,0.0059,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.4e-05,6.9e-05,0.0072,0.026,0.033,0.0054,0.28,0.32,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32090000,0.73,0.00088,-0.0014,0.68,-1.5,-0.93,0.78,-13,-6.1,-3.7e+02,-0.0013,-0.0058,-0.00022,0.0083,0.0064,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7e-05,0.0072,0.027,0.035,0.0054,0.29,0.33,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,8.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32190000,0.73,0.00078,-0.0024,0.69,-1.5,-0.91,0.78,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-0.00023,0.0095,0.0067,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.2e-05,6.9e-05,0.007,0.026,0.033,0.0054,0.29,0.33,0.031,3e-07,3.1e-07,2.5e-06,0.0039,0.0038,8.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32290000,0.73,0.0005,-0.0031,0.69,-1.5,-0.91,0.77,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-0.00023,0.0093,0.0072,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.3e-05,6.9e-05,0.007,0.027,0.035,0.0054,0.3,0.34,0.031,3e-07,3.1e-07,2.5e-06,0.0039,0.0038,8.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32390000,0.73,0.00041,-0.0039,0.69,-1.5,-0.89,0.77,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-0.00024,0.0099,0.0071,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.9e-05,6.8e-05,0.0067,0.025,0.033,0.0054,0.3,0.34,0.031,2.9e-07,3e-07,2.5e-06,0.0039,0.0037,8.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32490000,0.73,0.00026,-0.0041,0.69,-1.4,-0.88,0.78,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-0.00024,0.0097,0.0075,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8e-05,6.9e-05,0.0067,0.027,0.035,0.0054,0.31,0.35,0.031,2.9e-07,3e-07,2.5e-06,0.0039,0.0037,8.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32590000,0.73,0.00039,-0.0045,0.69,-1.4,-0.87,0.78,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0078,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.7e-05,6.8e-05,0.0065,0.025,0.033,0.0053,0.31,0.35,0.031,2.9e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32690000,0.73,0.00033,-0.0046,0.69,-1.4,-0.86,0.77,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0081,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.8e-05,6.8e-05,0.0065,0.027,0.035,0.0053,0.32,0.35,0.031,2.9e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32790000,0.72,0.00048,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0081,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.5e-05,6.7e-05,0.0063,0.025,0.032,0.0053,0.32,0.35,0.031,2.8e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32890000,0.72,0.00055,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0086,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.6e-05,6.8e-05,0.0063,0.027,0.034,0.0053,0.33,0.36,0.031,2.8e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32990000,0.72,0.00079,-0.0046,0.69,-1.3,-0.82,0.77,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00026,0.012,0.009,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.4e-05,6.7e-05,0.0061,0.025,0.032,0.0053,0.33,0.36,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33090000,0.72,0.00074,-0.0047,0.69,-1.3,-0.82,0.76,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00026,0.012,0.0094,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.4e-05,6.8e-05,0.0061,0.027,0.034,0.0053,0.34,0.37,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33190000,0.72,0.0043,-0.0039,0.7,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.0095,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.2e-05,6.7e-05,0.0059,0.025,0.032,0.0053,0.34,0.37,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,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.00027,0.012,0.0098,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.3e-05,6.7e-05,0.0059,0.027,0.033,0.0053,0.35,0.38,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33390000,0.57,0.014,-0.0037,0.82,-1.2,-0.77,0.88,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.1e-05,6.6e-05,0.0057,0.025,0.03,0.0053,0.35,0.38,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33490000,0.43,0.0073,-0.0012,0.9,-1.2,-0.76,0.89,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.1e-05,6.7e-05,0.0057,0.026,0.032,0.0053,0.36,0.39,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33590000,0.27,0.0011,-0.0037,0.96,-1.2,-0.76,0.86,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00028,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.9e-05,6.5e-05,0.0055,0.025,0.03,0.0052,0.35,0.39,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33690000,0.11,-0.0025,-0.0068,0.99,-1.1,-0.75,0.87,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00028,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7e-05,6.6e-05,0.0055,0.026,0.032,0.0053,0.37,0.4,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33790000,-0.065,-0.0044,-0.0086,1,-1.1,-0.73,0.85,-16,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00029,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.7e-05,6.4e-05,0.0054,0.025,0.031,0.0052,0.36,0.4,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33890000,-0.23,-0.0059,-0.0092,0.97,-1,-0.7,0.83,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00029,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.7e-05,6.4e-05,0.0054,0.026,0.033,0.0052,0.38,0.41,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33990000,-0.38,-0.0046,-0.013,0.92,-0.95,-0.65,0.81,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0003,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.5e-05,6.2e-05,0.0052,0.026,0.032,0.0052,0.37,0.41,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34090000,-0.49,-0.0038,-0.014,0.87,-0.89,-0.6,0.81,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0003,0.012,0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.5e-05,6.2e-05,0.0052,0.028,0.035,0.0052,0.39,0.42,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0036,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34190000,-0.56,-0.0036,-0.013,0.83,-0.86,-0.55,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00031,0.011,0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.1e-05,5.9e-05,0.005,0.028,0.034,0.0052,0.38,0.42,0.03,2.6e-07,2.6e-07,2.5e-06,0.0038,0.0036,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34290000,-0.6,-0.0046,-0.0095,0.8,-0.81,-0.49,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00031,0.011,0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.1e-05,5.9e-05,0.005,0.03,0.038,0.0052,0.39,0.43,0.03,2.6e-07,2.6e-07,2.5e-06,0.0038,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34390000,-0.63,-0.0052,-0.0067,0.78,-0.79,-0.45,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00032,0.0086,0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.7e-05,5.6e-05,0.0049,0.03,0.036,0.0052,0.39,0.43,0.03,2.6e-07,2.6e-07,2.5e-06,0.0037,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34490000,-0.64,-0.0061,-0.0045,0.76,-0.73,-0.4,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00032,0.0084,0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.7e-05,5.6e-05,0.0049,0.033,0.04,0.0052,0.4,0.44,0.03,2.6e-07,2.6e-07,2.5e-06,0.0037,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34590000,-0.65,-0.0061,-0.0032,0.76,-0.72,-0.37,0.8,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00033,0.0041,0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.3e-05,5.2e-05,0.0047,0.032,0.038,0.0052,0.4,0.44,0.03,2.6e-07,2.6e-07,2.5e-06,0.0036,0.0035,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34690000,-0.66,-0.0065,-0.0023,0.75,-0.66,-0.32,0.8,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00033,0.004,0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.3e-05,5.2e-05,0.0047,0.036,0.042,0.0052,0.41,0.45,0.03,2.6e-07,2.6e-07,2.5e-06,0.0036,0.0035,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34790000,-0.66,-0.0058,-0.0019,0.75,-0.65,-0.3,0.79,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00035,-0.0013,0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.034,0.039,0.0052,0.41,0.45,0.03,2.6e-07,2.6e-07,2.5e-06,0.0034,0.0034,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34890000,-0.67,-0.0059,-0.0018,0.75,-0.6,-0.25,0.79,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00035,-0.0014,0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.038,0.044,0.0052,0.42,0.46,0.03,2.6e-07,2.6e-07,2.5e-06,0.0034,0.0033,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34990000,-0.67,-0.013,-0.0043,0.74,0.45,0.35,-0.044,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.042,0.058,0.0054,0.42,0.46,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35090000,-0.67,-0.013,-0.0043,0.74,0.58,0.38,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.046,0.064,0.0055,0.43,0.47,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35190000,-0.67,-0.013,-0.0044,0.74,0.61,0.42,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.051,0.068,0.0055,0.44,0.47,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35290000,-0.67,-0.013,-0.0044,0.74,0.64,0.46,-0.1,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.055,0.073,0.0055,0.46,0.48,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35390000,-0.67,-0.013,-0.0044,0.74,0.67,0.51,-0.097,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.06,0.078,0.0055,0.47,0.49,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35490000,-0.67,-0.013,-0.0044,0.74,0.7,0.55,-0.095,-17,-7.9,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.065,0.083,0.0055,0.49,0.51,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35590000,-0.67,-0.013,-0.0044,0.74,0.73,0.59,-0.095,-17,-7.9,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.07,0.088,0.0056,0.51,0.52,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35690000,-0.67,-0.013,-0.0044,0.74,0.76,0.63,-0.092,-16,-7.8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0045,0.075,0.094,0.0056,0.53,0.54,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35790000,-0.67,-0.013,-0.0044,0.74,0.79,0.68,-0.09,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.081,0.1,0.0056,0.55,0.56,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.023 -35890000,-0.67,-0.013,-0.0044,0.74,0.82,0.72,-0.086,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.087,0.11,0.0056,0.57,0.58,0.031,2.6e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.048 -35990000,-0.67,-0.013,-0.0044,0.74,0.85,0.76,-0.083,-16,-7.6,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.093,0.11,0.0056,0.6,0.6,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.073 -36090000,-0.67,-0.013,-0.0044,0.74,0.88,0.8,-0.08,-16,-7.5,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.1,0.12,0.0056,0.62,0.63,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.099 -36190000,-0.67,-0.013,-0.0044,0.74,0.92,0.85,-0.075,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0084,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.11,0.13,0.0056,0.66,0.66,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.12 -36290000,-0.67,-0.013,-0.0044,0.74,0.95,0.89,-0.07,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0083,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.11,0.13,0.0057,0.69,0.69,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.15 -36390000,-0.67,-0.013,-0.0044,0.74,0.98,0.93,-0.067,-16,-7.3,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0082,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.12,0.14,0.0057,0.72,0.73,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.17 -36490000,-0.67,-0.013,-0.0044,0.74,1,0.98,-0.063,-16,-7.2,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0082,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.13,0.15,0.0057,0.76,0.76,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.2 -36590000,-0.67,-0.013,-0.0044,0.74,1,1,-0.057,-16,-7.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0081,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.14,0.16,0.0057,0.81,0.81,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.23 -36690000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.053,-16,-7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.008,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.14,0.17,0.0057,0.85,0.86,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.25 -36790000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.047,-15,-6.9,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0079,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.15,0.17,0.0057,0.9,0.91,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.28 -36890000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.042,-15,-6.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0078,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.16,0.18,0.0057,0.96,0.96,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.3 -36990000,-0.67,-0.013,-0.0043,0.74,1.2,1.2,-0.037,-15,-6.6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0077,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.17,0.19,0.0057,1,1,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.33 -37090000,-0.67,-0.013,-0.0042,0.74,1.2,1.2,-0.031,-15,-6.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0076,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.18,0.2,0.0057,1.1,1.1,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.35 -37190000,-0.67,-0.013,-0.0042,0.74,1.2,1.3,-0.025,-15,-6.4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0076,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.19,0.21,0.0057,1.1,1.2,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -37290000,-0.67,-0.013,-0.0042,0.74,1.3,1.3,-0.02,-15,-6.2,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.2,0.22,0.0057,1.2,1.2,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -37390000,-0.67,-0.013,-0.0042,0.74,1.3,1.4,-0.015,-15,-6.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.21,0.23,0.0057,1.3,1.3,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -37490000,-0.67,-0.013,-0.0041,0.74,1.3,1.4,-0.009,-15,-6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.22,0.24,0.0057,1.4,1.4,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -37590000,-0.67,-0.013,-0.0041,0.74,1.4,1.4,-0.0023,-14,-5.8,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0074,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.23,0.25,0.0057,1.5,1.5,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -37690000,-0.67,-0.013,-0.0041,0.74,1.4,1.5,0.0051,-14,-5.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0071,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0045,0.24,0.26,0.0057,1.6,1.6,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -37790000,-0.67,-0.013,-0.0042,0.74,1.4,1.5,0.012,-14,-5.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.007,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0045,0.25,0.28,0.0057,1.7,1.7,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.54 -37890000,-0.67,-0.013,-0.0042,0.74,1.4,1.6,0.018,-14,-5.4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.007,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0046,0.26,0.29,0.0057,1.8,1.8,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -37990000,-0.67,-0.013,-0.0042,0.74,1.5,1.6,0.026,-14,-5.2,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0069,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.27,0.3,0.0057,1.9,2,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.59 -38090000,-0.67,-0.013,-0.0042,0.74,1.5,1.7,0.035,-14,-5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.28,0.31,0.0057,2,2.1,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -38190000,-0.67,-0.013,-0.0042,0.74,1.5,1.7,0.041,-14,-4.9,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.29,0.32,0.0056,2.1,2.2,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.64 -38290000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.047,-13,-4.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.3,0.33,0.0057,2.3,2.4,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.67 -38390000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.053,-13,-4.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.32,0.35,0.0056,2.4,2.5,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.69 -38490000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.059,-13,-4.3,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.8e-05,0.0046,0.33,0.36,0.0056,2.6,2.7,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.72 -38590000,-0.67,-0.013,-0.004,0.74,1.7,1.9,0.064,-13,-4.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.8e-05,0.0046,0.34,0.37,0.0056,2.8,2.9,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.75 -38690000,-0.67,-0.013,-0.004,0.74,1.7,1.9,0.07,-13,-4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.35,0.39,0.0056,2.9,3.1,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.77 -38790000,-0.67,-0.013,-0.004,0.74,1.7,2,0.076,-13,-3.8,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.37,0.4,0.0056,3.1,3.3,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.8 -38890000,-0.67,-0.014,-0.0041,0.74,1.7,2,0.58,-12,-3.6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.38,0.41,0.0056,3.3,3.5,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +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.0096,0.00085,-0.0018,-3.7e+02,-0.0015,-0.0058,-7.9e-05,-0.0022,0.0014,-0.1,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.078,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.013,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.023,0.0016,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.3e-05,-0.0024,0.0014,-0.1,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.08,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.012,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.026,0.0018,-0.00082,-3.7e+02,-0.0016,-0.0059,-7.9e-05,-0.0026,0.002,-0.11,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.073,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.012,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.03,0.0023,-0.0017,-3.7e+02,-0.0015,-0.0059,-8.1e-05,-0.0026,0.0019,-0.11,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.078,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.011,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.024,0.0026,-0.00085,-3.7e+02,-0.0015,-0.0059,-8e-05,-0.0027,0.0023,-0.11,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.072,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.011,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.02,0.0029,-0.0015,-3.7e+02,-0.0015,-0.0058,-8.1e-05,-0.0027,0.0022,-0.11,0.21,-3.7e-06,0.43,-0.00024,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.075,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.011,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.014,0.0048,-0.0026,-3.7e+02,-0.0013,-0.0057,-7.9e-05,-0.0027,0.0032,-0.11,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.011,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.019,0.0057,-0.0023,-3.7e+02,-0.0014,-0.0056,-7.5e-05,-0.0026,0.0031,-0.11,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.11,0.078,0.078,0.074,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.011,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.0077,0.0067,-0.0032,-3.7e+02,-0.0013,-0.0056,-7.8e-05,-0.0025,0.0042,-0.11,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.084,0.062,0.062,0.069,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.01,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.0074,0.0076,-0.0034,-3.7e+02,-0.0013,-0.0057,-8.3e-05,-0.0029,0.0045,-0.11,0.21,-3e-06,0.43,-0.00022,0.00073,-0.00011,0,0,-3.6e+02,0.00098,0.00091,0.038,0.085,0.087,0.078,0.068,0.068,0.072,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.01,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.00081,0.0017,0.0055,-0.003,-3.7e+02,-0.0013,-0.0058,-8.6e-05,-0.0035,0.0043,-0.11,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.063,0.056,0.056,0.068,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.01,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.0025,0.0055,-0.0039,-3.7e+02,-0.0012,-0.0059,-9.3e-05,-0.0041,0.0051,-0.11,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.058,0.062,0.062,0.069,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.01,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.0034,0.0044,-0.0032,-3.7e+02,-0.0012,-0.0059,-9.4e-05,-0.0047,0.0053,-0.11,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.049,0.052,0.052,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.01,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.0079,0.0044,-0.004,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0055,0.0054,-0.11,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.046,0.059,0.059,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.01,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.0009,-0.0098,0.0024,-0.002,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0073,0.0056,-0.11,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.039,0.05,0.05,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.01,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.011,0.0016,-0.0027,-3.7e+02,-0.001,-0.006,-0.0001,-0.008,0.0061,-0.11,0.21,-1.9e-06,0.43,-5.5e-05,0.00047,-0.00032,0,0,-3.6e+02,0.00065,0.00062,0.038,0.079,0.082,0.037,0.057,0.057,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.01,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.016,-0.0001,-7.7e-05,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0076,0.0067,-0.11,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.033,0.049,0.049,0.061,9.2e-06,1.6e-05,2.3e-06,0.026,0.027,0.01,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.022,-0.0014,0.00091,-3.7e+02,-0.0012,-0.0059,-9.5e-05,-0.0065,0.0059,-0.11,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.031,0.056,0.056,0.061,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.01,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.017,0.0015,0.00037,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0064,0.0062,-0.11,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.028,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.01,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.016,0.0011,0.00073,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0069,0.0058,-0.11,0.21,-2e-06,0.43,-8.2e-05,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.073,0.076,0.028,0.055,0.056,0.059,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.01,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.015,0.0025,0.00024,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0055,0.0075,-0.11,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.026,0.048,0.048,0.057,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.01,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.0071,0.0027,-0.018,0.0017,3.7e-05,-3.7e+02,-0.0011,-0.0059,-0.0001,-0.006,0.0087,-0.11,0.21,-2.7e-06,0.43,-0.00015,0.00054,-0.00025,0,0,-3.6e+02,0.00042,0.00042,0.037,0.069,0.072,0.026,0.055,0.055,0.057,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.01,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.023,-0.0033,0.00021,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0053,0.008,-0.11,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.025,0.047,0.047,0.055,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.0099,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.027,-0.0058,0.00079,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0035,0.0094,-0.11,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.025,0.055,0.055,0.055,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.0098,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.03,-0.0081,0.00026,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0051,0.0082,-0.11,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.024,0.047,0.047,0.053,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.0097,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.029,-0.0096,0.0002,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0064,0.0078,-0.11,0.21,-2.8e-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.025,0.054,0.055,0.054,6e-06,1e-05,2.3e-06,0.018,0.021,0.0096,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.03,-0.0018,0.0005,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.004,0.0082,-0.11,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.025,0.047,0.047,0.052,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.0094,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.00014,-0.03,-0.0029,-6.9e-05,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0051,0.0098,-0.11,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.025,0.054,0.054,0.052,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.0094,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.027,0.0028,0.00014,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0033,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.025,0.047,0.047,0.051,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0091,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.024,0.0034,0.0003,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0048,0.0097,-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.027,0.054,0.054,0.051,5.1e-06,8.9e-06,2.3e-06,0.015,0.018,0.0091,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.02,0.0025,0.00042,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0042,0.009,-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.026,0.047,0.047,0.05,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0088,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.019,0.0027,0.0008,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0043,0.0082,-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.028,0.054,0.054,0.05,4.7e-06,8.2e-06,2.3e-06,0.014,0.017,0.0087,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.8e-05,0.0028,-0.021,0.0015,0.00038,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0041,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.028,0.046,0.047,0.05,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0084,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.00091,0.0053,-0.025,0.0017,0.0011,-3.7e+02,-0.001,-0.0059,-9.9e-05,-0.0035,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.029,0.053,0.054,0.05,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.027,0.0024,-0.00073,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0021,0.009,-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.029,0.046,0.046,0.049,4.2e-06,7.3e-06,2.3e-06,0.012,0.016,0.0079,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.031,0.003,-0.00056,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0035,0.0079,-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.03,0.053,0.053,0.05,4e-06,7.1e-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 +13990000,0.71,0.00066,-0.013,0.71,0.0019,0.00054,-0.03,0.0036,-0.0019,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0022,0.0084,-0.12,0.21,-2e-06,0.43,-0.00018,0.00065,-0.00013,0,0,-3.6e+02,0.00021,0.00022,0.037,0.037,0.039,0.03,0.046,0.046,0.05,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0074,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.031,0.0036,-0.0013,-3.7e+02,-0.0011,-0.0059,-9.4e-05,-0.00071,0.0073,-0.12,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.031,0.053,0.053,0.05,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.0073,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.033,0.0057,-0.001,-3.7e+02,-0.0011,-0.0059,-9.3e-05,-0.00025,0.0071,-0.12,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.03,0.046,0.046,0.05,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0069,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.032,0.0059,-0.00065,-3.7e+02,-0.0011,-0.0058,-9.2e-05,0.0006,0.007,-0.12,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.031,0.052,0.052,0.051,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0067,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.0071,0.005,-0.034,0.0077,-0.00036,-3.7e+02,-0.0011,-0.0058,-8.9e-05,0.00028,0.0055,-0.12,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.031,0.046,0.046,0.05,3.4e-06,6e-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 +14490000,0.71,0.00052,-0.013,0.71,0.008,0.0065,-0.037,0.0088,0.00011,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.001,0.005,-0.12,0.21,-4.3e-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.032,0.052,0.052,0.051,3.3e-06,5.8e-06,2.3e-06,0.01,0.014,0.0062,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.037,0.006,-0.0015,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.0019,0.0048,-0.12,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.031,0.045,0.045,0.051,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0058,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.034,0.0068,-0.00088,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0019,0.0039,-0.12,0.21,4.2e-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.032,0.051,0.052,0.051,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0056,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.0056,0.0016,-0.03,0.0042,-0.0021,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.002,0.0038,-0.12,0.21,-1.5e-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.031,0.045,0.045,0.051,3e-06,5.2e-06,2.3e-06,0.0097,0.013,0.0052,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.033,0.005,-0.0018,-3.7e+02,-0.001,-0.0058,-8.6e-05,-0.0023,0.0032,-0.12,0.21,2.5e-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.031,0.051,0.051,0.052,2.9e-06,5.1e-06,2.3e-06,0.0096,0.013,0.0051,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.029,0.004,-0.0017,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0028,0.0037,-0.12,0.21,5.1e-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.03,0.045,0.045,0.051,2.8e-06,4.9e-06,2.3e-06,0.0094,0.012,0.0048,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.032,0.0047,-0.0016,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0029,0.0041,-0.12,0.21,-5.2e-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.052,2.7e-06,4.8e-06,2.3e-06,0.0092,0.012,0.0046,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.0073,0.003,-0.029,0.0039,-0.0015,-3.7e+02,-0.001,-0.0058,-9e-05,-0.0036,0.0044,-0.12,0.21,-4.8e-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.052,2.6e-06,4.6e-06,2.3e-06,0.009,0.012,0.0043,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.0078,0.0041,-0.027,0.0044,-0.00097,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0026,0.0042,-0.12,0.21,-3.8e-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.052,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0041,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.0071,0.0054,-0.025,0.0017,-0.00041,-3.7e+02,-0.001,-0.0058,-8.3e-05,-0.0018,0.0028,-0.12,0.21,3.5e-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.029,0.044,0.044,0.051,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0038,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.025,0.0024,-0.00036,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0022,0.0041,-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.053,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0037,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.023,8.4e-05,-0.00068,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0029,0.0048,-0.12,0.21,-4.5e-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.028,0.044,0.044,0.052,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0034,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.0075,0.0037,-0.024,0.00059,-0.00037,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0024,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.028,0.049,0.049,0.052,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.0033,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.026,0.00049,-0.0016,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0026,0.0054,-0.12,0.21,-8.7e-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.027,0.043,0.044,0.051,2.2e-06,3.9e-06,2.3e-06,0.0081,0.011,0.0031,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.024,0.0011,-0.0014,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0019,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.027,0.048,0.049,0.052,2.1e-06,3.8e-06,2.3e-06,0.008,0.011,0.003,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.02,0.00076,-0.0019,-3.7e+02,-0.0011,-0.0059,-8.4e-05,-0.0013,0.005,-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.026,0.043,0.043,0.051,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0028,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.016,0.0017,-0.0011,-3.7e+02,-0.0011,-0.0058,-8e-05,-0.00049,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.025,0.048,0.048,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0027,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.015,0.001,-0.00095,-3.7e+02,-0.0011,-0.0058,-7.9e-05,0.00025,0.0039,-0.13,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.025,0.043,0.043,0.051,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0025,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.016,0.0023,5.7e-05,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.00057,0.0026,-0.13,0.21,-5.6e-07,0.43,-0.00015,0.00064,-5.9e-06,0,0,-3.6e+02,0.00015,0.00014,0.037,0.023,0.025,0.024,0.047,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0024,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.015,0.0013,-0.00022,-3.7e+02,-0.0011,-0.0058,-7.6e-05,0.0017,0.0038,-0.13,0.21,-1.3e-06,0.43,-0.00018,0.00064,-2.1e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.023,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0074,0.0098,0.0022,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.018,0.0018,0.00032,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.0026,0.004,-0.13,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.023,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0021,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.018,-0.00051,0.0023,-3.7e+02,-0.0012,-0.0058,-7.6e-05,0.0027,0.0037,-0.13,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.022,0.042,0.042,0.051,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0095,0.002,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.0077,0.0062,-0.015,0.00033,0.0026,-3.7e+02,-0.0012,-0.0058,-7.9e-05,0.0021,0.0044,-0.13,0.21,-1.8e-06,0.43,-0.00018,0.00062,-3.4e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.021,0.024,0.022,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0019,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.014,-0.0016,0.0042,-3.7e+02,-0.0012,-0.0058,-8e-05,0.0019,0.004,-0.13,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.021,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0092,0.0018,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.011,-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.021,0.046,0.047,0.051,1.6e-06,2.8e-06,2.3e-06,0.007,0.0091,0.0017,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.0056,-0.01,-0.0021,0.0025,-3.7e+02,-0.0012,-0.0059,-8.2e-05,0.0022,0.0057,-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.02,0.041,0.042,0.05,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0016,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.01,-0.002,0.0032,-3.7e+02,-0.0012,-0.0059,-8.1e-05,0.0031,0.006,-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.02,0.046,0.047,0.05,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0015,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.011,-0.0028,0.0021,-3.7e+02,-0.0012,-0.0059,-7.7e-05,0.0039,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.019,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0087,0.0015,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.0067,-0.0026,0.0025,-3.7e+02,-0.0012,-0.0059,-7.9e-05,0.0042,0.0069,-0.13,0.21,-3.5e-06,0.43,-0.00022,0.00061,-5.4e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.019,0.022,0.019,0.045,0.046,0.049,1.5e-06,2.5e-06,2.3e-06,0.0067,0.0086,0.0014,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.0047,-0.0024,0.0016,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.005,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.018,0.041,0.041,0.048,1.4e-06,2.4e-06,2.2e-06,0.0066,0.0085,0.0013,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.0092,0.0093,-0.003,-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.018,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0013,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.0025,-0.001,0.0013,-3.7e+02,-0.0012,-0.0059,-7e-05,0.0048,0.0067,-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.0012,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.0019,1.8e-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.017,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.00058,1.4e-05,0.0029,-3.7e+02,-0.0012,-0.0058,-6e-05,0.0058,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.048,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.0011,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.00068,0.0016,0.0045,-3.7e+02,-0.0012,-0.0058,-5.7e-05,0.0057,0.0047,-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.048,1.3e-06,2.2e-06,2.2e-06,0.0062,0.008,0.001,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.0019,0.0018,0.0036,-3.7e+02,-0.0012,-0.0058,-5.6e-05,0.0054,0.005,-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.016,0.04,0.041,0.047,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0078,0.00098,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.0043,0.0035,0.0037,-3.7e+02,-0.0012,-0.0059,-6.2e-05,0.0049,0.006,-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.016,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00095,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.0056,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.015,0.04,0.04,0.047,1.2e-06,2e-06,2.2e-06,0.0061,0.0076,0.0009,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.0068,0.0061,0.0041,-3.7e+02,-0.0012,-0.0059,-6e-05,0.0046,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.015,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00087,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.008,0.0068,0.0042,-3.7e+02,-0.0012,-0.0059,-5.4e-05,0.0044,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.046,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00082,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.0076,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.046,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.0008,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.0058,0.0074,0.0054,-3.7e+02,-0.0012,-0.0058,-4.5e-05,0.0057,0.0047,-0.13,0.21,-3.7e-06,0.43,-0.00025,0.00065,2.4e-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.8e-06,2.2e-06,0.0058,0.0073,0.00076,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.0039,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.00073,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.0035,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.045,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.0007,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,0.0042,0.01,0.0075,-3.7e+02,-0.0012,-0.0058,-4e-05,0.0062,0.0048,-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.045,1e-06,1.7e-06,2.2e-06,0.0057,0.007,0.00068,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.0028,0.01,0.0068,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0068,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.00065,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.0059,0.012,0.0084,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0074,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.00063,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.0059,0.012,0.0076,-3.7e+02,-0.0013,-0.0059,-2.7e-05,0.0079,0.0054,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00066,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.044,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.0006,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.0086,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.044,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00058,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.012,0.012,0.0079,-3.7e+02,-0.0013,-0.0059,-2.4e-05,0.0077,0.0057,-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.012,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0054,0.0066,0.00056,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.0088,0.014,0.01,-3.7e+02,-0.0013,-0.0058,-1.8e-05,0.0077,0.005,-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.00054,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.0081,0.012,0.0095,-3.7e+02,-0.0013,-0.0058,-6.7e-06,0.0085,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.00052,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.0096,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.8e-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.00051,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.01,0.011,0.009,-3.7e+02,-0.0013,-0.0059,-5.6e-06,0.0093,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.011,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00049,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.011,0.014,0.011,-3.7e+02,-0.0013,-0.0058,2.6e-06,0.0091,0.0047,-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.011,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0052,0.0063,0.00047,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.014,0.012,0.011,-3.7e+02,-0.0013,-0.0058,1.8e-05,0.0095,0.0039,-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.9e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00046,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.014,0.013,0.013,-3.7e+02,-0.0013,-0.0058,2.8e-05,0.01,0.0031,-0.13,0.21,-4.7e-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.042,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.1 +20190000,0.71,0.0007,-0.013,0.7,0.012,0.012,0.017,0.011,0.012,-3.7e+02,-0.0013,-0.0058,3.7e-05,0.0098,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.01,0.037,0.039,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00043,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.015,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.0099,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.006,0.00042,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.017,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.0097,0.037,0.039,0.041,7.3e-07,1.1e-06,2e-06,0.005,0.0059,0.0004,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.016,0.011,0.012,-3.7e+02,-0.0013,-0.0058,4.2e-05,0.01,0.0031,-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.0096,0.041,0.043,0.041,7.2e-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.2 +20590000,0.71,0.00074,-0.013,0.7,0.0078,0.0076,0.013,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.00071,5e-05,0,0,-3.6e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0093,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0058,0.00038,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.015,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.0093,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.0049,0.0058,0.00037,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.015,0.0084,0.01,-3.7e+02,-0.0013,-0.0058,5.1e-05,0.011,0.0036,-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.0091,0.037,0.039,0.04,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00036,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.0068,0.014,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.1e-05,0,0,-3.6e+02,9.8e-05,8.8e-05,0.036,0.014,0.017,0.009,0.04,0.043,0.04,6.6e-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.3 +20990000,0.71,0.00084,-0.013,0.7,0.0044,0.0045,0.015,0.009,0.0099,-3.7e+02,-0.0013,-0.0058,6.3e-05,0.011,0.0034,-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.0088,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0048,0.0056,0.00034,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.015,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.0088,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.014,0.011,0.0091,-3.7e+02,-0.0013,-0.0058,6.9e-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.0086,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.016,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.0085,0.04,0.043,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.4 +21390000,0.71,0.00088,-0.013,0.7,0.004,0.00085,0.016,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.0084,0.037,0.039,0.039,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.00031,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.015,0.01,0.0098,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0025,-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.0083,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.015,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.005,0.0021,0.017,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.00029,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.015,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.008,0.036,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00028,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.016,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.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 +21990000,0.71,0.00085,-0.013,0.7,0.0026,0.0054,0.016,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.0078,0.036,0.038,0.038,5.4e-07,8e-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,0.01 +22090000,0.71,0.00088,-0.013,0.7,0.0025,0.007,0.015,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.0078,0.04,0.042,0.037,5.4e-07,7.9e-07,1.8e-06,0.0045,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.015,0.0053,0.011,-3.7e+02,-0.0013,-0.0058,7.6e-05,0.012,0.0022,-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.00026,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.015,0.0057,0.012,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.011,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.0076,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.017,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.0075,0.036,0.038,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00025,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.018,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.017,0.00096,0.01,-3.7e+02,-0.0014,-0.0058,8.5e-05,0.013,0.0028,-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.00024,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.018,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.019,-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.2e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.012,0.015,0.0072,0.036,0.038,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00023,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.021,-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.0072,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.022,-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.0071,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.022,-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.00076,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.00022,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.024,-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.024,-0.0081,0.0084,-3.7e+02,-0.0014,-0.0058,8.6e-05,0.012,0.0035,-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.022,-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.012,-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.00078,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.043,-0.011,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0033,-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.094,-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.0002,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.25,-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.0066,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00019,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.7e-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.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 +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.0065,0.036,0.038,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 +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.00018,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.003,-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.6e-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.00017,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.004,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.6e-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.034,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.00016,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.0061,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.0083,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.0061,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.0032,-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.8e-05,-4.9e-05,0,0,-3.7e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.006,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,-2e-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.00015,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.0059,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.0043,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.00014,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.0058,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.00069,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.00074,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.0058,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.00021,-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.00013,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.003,-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.0037,-0.00088,-0.13,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.0057,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.00036,-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.0042,0.00057,-0.12,0.21,-7.6e-05,0.44,-0.0065,0.0014,-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.077,-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.00012,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.0039,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.004,0.0017,-0.12,0.21,-6.8e-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.0037,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,-9.3e-06,0.0015,0.69,-2.6,-1.2,0.98,-6,-2.9,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0032,0.0023,-0.12,0.21,-9.2e-05,0.44,-0.0091,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.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28890000,0.73,5.4e-07,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.0031,-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.0057,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.2e-05,0.44,-0.011,-0.00038,-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.001,0.0035,-0.12,0.21,-0.00013,0.44,-0.011,-0.00062,-0.0041,0,0,-3.7e+02,8.7e-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.00098,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.0057,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.00025,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.00024,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.00037,0.0047,-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.00011,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.00031,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.0013,0.0048,-0.12,0.21,-0.00017,0.44,-0.012,-0.0018,-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.0015,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.0054,-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.0048,-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.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.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,0.0001,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.0049,-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.9e-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.0047,-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.8e-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.0031,0.005,-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.0044,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00079,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.7e-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.0045,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.5e-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.4e-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.005,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.3e-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.0049,0.0052,-0.11,0.21,-0.0003,0.43,-0.011,-0.0029,8.8e-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.8e-05,0.0058,0.0049,-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.2e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31690000,0.73,0.0017,0.0014,0.68,-1.6,-0.97,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,5e-05,0.0055,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.5e-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,9.1e-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.4e-06,0.007,0.0055,-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,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.3e-06,0.0068,0.006,-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.7e-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.9e-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.0066,-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.0065,-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.8e-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.0069,-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.7e-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.0077,0.0073,-0.11,0.21,-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.8e-05,0.0081,0.0073,-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.6e-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.0079,-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.5e-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.0083,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.0085,-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.4e-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.0088,-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.0089,-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.0089,-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.00018,0.0085,0.0089,-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.0089,-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.0089,-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.4e-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.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0085,0.009,-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.0084,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.0002,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.3e-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.78,-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.2e-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,8.1e-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.0082,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.8e-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,-7e-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,8.1e-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.72,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,8.1e-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,8.1e-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.091,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.04,-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,8.1e-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.04,-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.0039,0.74,0.85,0.72,-0.085,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.04,-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.082,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.04,-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,8e-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.074,-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.9e-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.2e-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.052,-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.0038,0.74,1.1,1.1,-0.046,-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.8e-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.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.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.7e-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.0089,-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.0024,-14,-5.9,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-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.6e-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.0049,-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.018,-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.0057,1.7,1.9,0.032,2.6e-07,2.8e-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.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.047,-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.6e-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.4e-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.064,-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.3e-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 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 91d3fb7de4fe..3c42e668968b 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -69,283 +69,283 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[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.0066,-0.012,0.19,0.0013,0.013,-0.037,0.0016,0.0058,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.17,0.17,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0026,0.0025,0.002,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7090000,0.98,-0.0065,-0.012,0.19,0.00038,0.018,-0.038,0.0017,0.0074,-0.056,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.19,0.19,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0024,0.0025,0.0014,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7190000,0.98,-0.0064,-0.012,0.19,0,0,-0.037,0.0016,0.0093,-0.058,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0014,0.0014,0.09,25,25,0.029,1e+02,1e+02,0.065,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0023,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7290000,0.98,-0.0064,-0.012,0.19,0.00075,0.0036,-0.034,0.0016,0.0094,-0.054,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0014,0.0014,0.09,25,25,0.028,1e+02,1e+02,0.064,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0022,0.0025,0.00086,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7390000,0.98,-0.0063,-0.012,0.19,-0.001,0.006,-0.032,0.0016,0.01,-0.052,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,25,25,0.027,1e+02,1e+02,0.064,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.002,0.0025,0.00073,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7490000,0.98,-0.0063,-0.012,0.19,0.0013,0.0084,-0.026,0.0017,0.01,-0.046,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,25,25,0.026,51,51,0.063,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0019,0.0025,0.00062,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7590000,0.98,-0.0064,-0.012,0.19,0.0022,0.011,-0.023,0.0018,0.011,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0016,0.0016,0.09,25,25,0.025,52,52,0.062,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0018,0.0025,0.00054,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7690000,0.98,-0.0064,-0.013,0.19,0.0019,0.014,-0.022,0.002,0.012,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0016,0.0016,0.09,24,24,0.025,35,35,0.062,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0017,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,1,1,2 -7790000,0.98,-0.0063,-0.013,0.19,0.0034,0.016,-0.025,0.0022,0.013,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,24,24,0.024,37,37,0.061,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0016,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,1,1,2 -7890000,0.98,-0.0063,-0.013,0.19,0.002,0.02,-0.025,0.0022,0.014,-0.045,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,24,24,0.023,29,29,0.06,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0015,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,1,1,2 -7990000,0.98,-0.0062,-0.013,0.19,0.0023,0.022,-0.022,0.0024,0.016,-0.042,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0018,0.0018,0.09,24,24,0.022,31,31,0.059,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0015,0.0025,0.00036,0.0025,0.0025,0.0025,0.0025,1,1,2 -8090000,0.98,-0.0061,-0.013,0.19,0.0037,0.025,-0.022,0.0026,0.016,-0.044,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0019,0.0019,0.09,23,23,0.022,25,25,0.059,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0014,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8190000,0.98,-0.0061,-0.012,0.19,0.0043,0.03,-0.018,0.003,0.019,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0019,0.0019,0.09,23,23,0.021,28,28,0.058,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0013,0.0025,0.00031,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8290000,0.98,-0.0061,-0.012,0.19,0.0064,0.033,-0.017,0.0032,0.02,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.002,0.002,0.09,21,21,0.02,24,24,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0013,0.0025,0.00029,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8390000,0.98,-0.0061,-0.012,0.19,0.0042,0.035,-0.016,0.0037,0.023,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.002,0.002,0.09,21,21,0.02,26,26,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0012,0.0025,0.00027,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8490000,0.98,-0.006,-0.012,0.19,0.0037,0.037,-0.017,0.0036,0.023,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,19,19,0.019,23,23,0.056,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0011,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8590000,0.98,-0.0059,-0.013,0.19,0.0048,0.04,-0.012,0.004,0.027,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0022,0.0022,0.09,19,19,0.018,26,26,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0011,0.0025,0.00024,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8690000,0.98,-0.0059,-0.013,0.19,0.0045,0.04,-0.014,0.0038,0.027,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0022,0.0022,0.09,17,17,0.018,23,23,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.001,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8790000,0.98,-0.0059,-0.013,0.19,0.006,0.043,-0.014,0.0043,0.031,-0.035,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0023,0.0023,0.09,17,17,0.018,25,25,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00099,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8890000,0.98,-0.006,-0.013,0.19,0.0056,0.043,-0.0093,0.0042,0.03,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0024,0.0024,0.09,15,15,0.017,22,22,0.054,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00094,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -8990000,0.98,-0.0059,-0.013,0.19,0.0048,0.048,-0.0085,0.0047,0.034,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0024,0.0024,0.09,15,15,0.017,25,25,0.054,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00091,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9090000,0.98,-0.0059,-0.013,0.19,0.0047,0.049,-0.0095,0.0044,0.033,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0025,0.0025,0.09,13,13,0.016,22,22,0.053,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00087,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9190000,0.98,-0.0058,-0.013,0.19,0.0083,0.052,-0.009,0.0051,0.038,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0026,0.0026,0.09,13,13,0.016,25,25,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00083,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9290000,0.98,-0.0057,-0.013,0.19,0.01,0.051,-0.0074,0.0051,0.036,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0027,0.0027,0.09,12,12,0.015,22,22,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0008,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9390000,0.98,-0.0056,-0.013,0.19,0.01,0.054,-0.0063,0.0062,0.041,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0027,0.0027,0.09,12,12,0.015,24,24,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00077,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9490000,0.98,-0.0056,-0.013,0.19,0.01,0.057,-0.0046,0.0072,0.047,-0.027,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0028,0.0028,0.09,12,12,0.015,27,27,0.051,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00074,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9590000,0.98,-0.0056,-0.013,0.19,0.0096,0.054,-0.0045,0.0069,0.044,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0029,0.0029,0.09,10,10,0.014,24,24,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00071,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9690000,0.98,-0.0056,-0.013,0.19,0.0096,0.057,-0.0016,0.0079,0.049,-0.027,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,10,10,0.014,26,26,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00068,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9790000,0.98,-0.0056,-0.013,0.19,0.01,0.057,-0.0029,0.0075,0.046,-0.028,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,8.9,8.9,0.014,23,23,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00066,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9890000,0.98,-0.0056,-0.013,0.19,0.013,0.059,-0.0016,0.0086,0.052,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0031,0.0031,0.09,8.9,8.9,0.013,25,25,0.049,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00063,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9990000,0.98,-0.0056,-0.013,0.19,0.014,0.057,-0.0009,0.0084,0.049,-0.031,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0032,0.0032,0.09,7.7,7.7,0.013,22,22,0.049,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00061,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -10090000,0.98,-0.0055,-0.013,0.19,0.012,0.058,0.00032,0.0097,0.054,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0033,0.0033,0.09,7.8,7.8,0.013,24,24,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00059,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10190000,0.98,-0.0055,-0.013,0.19,0.0099,0.057,0.0012,0.0091,0.05,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,6.8,6.8,0.012,21,21,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00057,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10290000,0.98,-0.0055,-0.013,0.19,0.011,0.06,0.00014,0.01,0.056,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,6.9,6.9,0.012,23,23,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00055,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10390000,0.98,-0.0055,-0.013,0.19,0.0071,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0056,-9.2e-05,-4.1e-06,3.9e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0035,0.0035,0.09,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00053,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10490000,0.98,-0.0054,-0.012,0.19,0.0085,0.0076,0.0071,0.0015,0.00075,-0.023,-0.0016,-0.0056,-9.2e-05,-1.1e-05,1.2e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00052,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0054,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-9.3e-05,-4.3e-05,-0.00011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.13,0.13,0.27,0.13,0.13,0.055,6.4e-05,6.4e-05,2.2e-06,0.04,0.04,0.00051,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10690000,0.98,-0.0053,-0.012,0.19,-5.7e-05,0.0066,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-9.3e-05,-4.4e-05,-0.00011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0037,0.0037,0.09,0.15,0.15,0.26,0.14,0.14,0.065,6.4e-05,6.4e-05,2.2e-06,0.04,0.04,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10790000,0.98,-0.0055,-0.012,0.19,0.0018,0.0029,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-9.5e-05,0.00011,-0.00023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.11,0.11,0.17,0.09,0.09,0.062,6e-05,6e-05,2.2e-06,0.04,0.04,0.00049,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10890000,0.98,-0.0054,-0.013,0.19,0.0019,0.0063,0.01,-0.00059,-0.0043,-0.018,-0.0016,-0.0057,-9.5e-05,0.00011,-0.00023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0037,0.0037,0.09,0.13,0.13,0.16,0.097,0.097,0.068,6e-05,6e-05,2.2e-06,0.04,0.04,0.00049,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -10990000,0.98,-0.0055,-0.013,0.19,0.0014,0.012,0.016,-0.00045,-0.0031,-0.012,-0.0015,-0.0057,-9.6e-05,0.00018,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,0.099,0.099,0.12,0.072,0.072,0.065,5.3e-05,5.3e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11090000,0.98,-0.0056,-0.013,0.19,0.0024,0.017,0.02,-0.0003,-0.0017,-0.0074,-0.0015,-0.0057,-9.6e-05,0.00018,-0.00031,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,0.12,0.12,0.11,0.079,0.079,0.069,5.3e-05,5.3e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11190000,0.98,-0.006,-0.013,0.19,0.0042,0.016,0.026,0.0011,-0.0019,-0.00041,-0.0015,-0.0057,-9.7e-05,0.00048,-0.0004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,0.099,0.099,0.083,0.062,0.062,0.066,4.4e-05,4.4e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11290000,0.98,-0.006,-0.013,0.19,0.0045,0.018,0.026,0.0015,-0.00014,-0.00017,-0.0015,-0.0057,-9.7e-05,0.00048,-0.0004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,0.12,0.12,0.077,0.07,0.07,0.069,4.4e-05,4.4e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11390000,0.98,-0.0062,-0.013,0.19,0.0027,0.015,0.016,0.00089,-0.00098,-0.0086,-0.0014,-0.0057,-0.0001,0.00067,-0.00066,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0025,0.0025,0.09,0.1,0.1,0.062,0.057,0.057,0.066,3.5e-05,3.5e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11490000,0.98,-0.0061,-0.013,0.19,0.0019,0.016,0.02,0.0011,0.00055,-0.0025,-0.0014,-0.0057,-0.0001,0.00067,-0.00066,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0026,0.0026,0.09,0.12,0.12,0.057,0.065,0.065,0.067,3.5e-05,3.5e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11590000,0.98,-0.0065,-0.012,0.19,0.0036,0.012,0.018,0.00085,-0.00049,-0.0036,-0.0013,-0.0057,-0.0001,0.00084,-0.00084,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,0.098,0.098,0.048,0.054,0.054,0.065,2.7e-05,2.7e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11690000,0.98,-0.0065,-0.012,0.19,0.0041,0.016,0.018,0.0012,0.00089,-0.005,-0.0013,-0.0057,-0.0001,0.00084,-0.00084,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,0.12,0.12,0.044,0.062,0.062,0.066,2.7e-05,2.7e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -11790000,0.98,-0.0069,-0.012,0.19,0.0028,0.0099,0.019,0.00069,-0.0019,-0.002,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,0.094,0.094,0.037,0.052,0.052,0.063,2.1e-05,2.1e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -11890000,0.98,-0.007,-0.012,0.19,0.0055,0.011,0.017,0.0011,-0.00093,-0.0013,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0018,0.0018,0.09,0.11,0.11,0.034,0.06,0.06,0.063,2.1e-05,2.1e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -11990000,0.98,-0.0072,-0.012,0.19,0.0085,0.011,0.015,0.0021,-0.0019,-0.005,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,0.089,0.089,0.03,0.05,0.05,0.061,1.6e-05,1.6e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -12090000,0.98,-0.0071,-0.012,0.19,0.01,0.011,0.018,0.0031,-0.00082,0.0011,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,0.11,0.11,0.027,0.059,0.059,0.06,1.6e-05,1.6e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12190000,0.98,-0.007,-0.012,0.19,0.0082,0.011,0.017,0.0018,0.00029,0.0029,-0.0012,-0.0058,-0.00011,0.0011,-0.0012,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0012,0.0012,0.09,0.083,0.083,0.024,0.05,0.05,0.058,1.2e-05,1.2e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12290000,0.98,-0.0071,-0.012,0.19,0.006,0.01,0.016,0.0025,0.0013,0.0039,-0.0012,-0.0058,-0.00011,0.0011,-0.0012,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.098,0.098,0.022,0.058,0.058,0.058,1.2e-05,1.2e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12390000,0.98,-0.0072,-0.012,0.19,0.0045,0.0068,0.014,0.0017,0.00041,-0.0021,-0.0012,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0011,0.0011,0.09,0.077,0.077,0.02,0.049,0.049,0.056,9.8e-06,9.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12490000,0.98,-0.0072,-0.012,0.19,0.0047,0.0078,0.018,0.0022,0.0011,-8.1e-05,-0.0012,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0011,0.0011,0.09,0.09,0.09,0.018,0.058,0.058,0.055,9.8e-06,9.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12590000,0.98,-0.0074,-0.012,0.19,0.0084,0.0013,0.019,0.0033,-0.0014,0.0017,-0.0011,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00094,0.00094,0.09,0.071,0.071,0.017,0.049,0.049,0.054,7.9e-06,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12690000,0.98,-0.0073,-0.012,0.19,0.009,-0.00085,0.019,0.0041,-0.0014,0.0033,-0.0011,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00095,0.00095,0.09,0.083,0.083,0.015,0.057,0.057,0.053,7.9e-06,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12790000,0.98,-0.0076,-0.012,0.19,0.011,-0.0041,0.021,0.0041,-0.0045,0.0054,-0.0011,-0.0058,-0.00011,0.0012,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00084,0.00084,0.09,0.066,0.066,0.014,0.049,0.049,0.051,6.5e-06,6.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12890000,0.98,-0.0076,-0.012,0.19,0.011,-0.0049,0.022,0.0052,-0.0049,0.0084,-0.0011,-0.0058,-0.00011,0.0012,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00085,0.00085,0.09,0.076,0.076,0.013,0.057,0.057,0.051,6.5e-06,6.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -12990000,0.98,-0.0075,-0.012,0.19,0.0087,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00076,0.00076,0.09,0.061,0.061,0.012,0.048,0.048,0.05,5.4e-06,5.4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13090000,0.98,-0.0076,-0.012,0.19,0.0098,-0.0027,0.02,0.0045,-0.0039,0.0085,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00077,0.00077,0.09,0.07,0.07,0.011,0.057,0.057,0.049,5.4e-06,5.4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13190000,0.98,-0.0076,-0.012,0.19,0.0048,-0.0043,0.019,0.001,-0.0046,0.0091,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00071,0.00071,0.09,0.057,0.057,0.011,0.048,0.048,0.047,4.6e-06,4.6e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13290000,0.98,-0.0076,-0.012,0.19,0.0047,-0.0052,0.016,0.0015,-0.005,0.0084,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00071,0.00071,0.09,0.065,0.065,0.01,0.056,0.056,0.047,4.6e-06,4.6e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13390000,0.98,-0.0075,-0.012,0.19,0.0037,-0.0033,0.016,0.00095,-0.0038,0.0091,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00066,0.00066,0.09,0.053,0.053,0.0094,0.048,0.048,0.046,4e-06,4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13490000,0.98,-0.0075,-0.012,0.19,0.0044,-0.0015,0.015,0.0014,-0.004,0.0053,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00066,0.00067,0.09,0.06,0.06,0.009,0.056,0.056,0.045,4e-06,4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13590000,0.98,-0.0075,-0.012,0.19,0.0086,-0.0018,0.017,0.0041,-0.0032,0.0038,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00062,0.00062,0.09,0.049,0.049,0.0085,0.048,0.048,0.044,3.5e-06,3.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13690000,0.98,-0.0074,-0.012,0.19,0.0088,-0.0031,0.017,0.0049,-0.0035,0.0064,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00063,0.00063,0.09,0.055,0.055,0.0082,0.055,0.055,0.044,3.5e-06,3.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13790000,0.98,-0.0074,-0.012,0.19,0.015,0.00083,0.017,0.0083,-0.001,0.0059,-0.0011,-0.0058,-0.00011,0.0011,-0.0015,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00059,0.00059,0.09,0.046,0.046,0.0078,0.047,0.047,0.042,3.1e-06,3.1e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13890000,0.98,-0.0073,-0.012,0.19,0.017,0.0016,0.018,0.0099,-0.00092,0.0081,-0.0011,-0.0058,-0.00011,0.0011,-0.0015,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0006,0.0006,0.09,0.052,0.051,0.0076,0.055,0.055,0.042,3.1e-06,3.1e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13990000,0.98,-0.0074,-0.012,0.19,0.016,0.002,0.017,0.0075,-0.0023,0.007,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00057,0.00057,0.066,0.043,0.043,0.0073,0.047,0.047,0.041,2.8e-06,2.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -14090000,0.98,-0.0074,-0.012,0.19,0.014,-0.0024,0.018,0.0091,-0.0024,0.0035,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00057,0.00057,0.066,0.048,0.048,0.0072,0.054,0.054,0.041,2.8e-06,2.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14190000,0.98,-0.0073,-0.012,0.19,0.011,-0.0011,0.018,0.0082,-0.0018,0.0037,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00055,0.00055,0.066,0.041,0.041,0.007,0.047,0.047,0.04,2.5e-06,2.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14290000,0.98,-0.0073,-0.012,0.19,0.013,-0.0011,0.016,0.0093,-0.0019,0.0079,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00055,0.00055,0.066,0.045,0.045,0.0069,0.054,0.054,0.039,2.5e-06,2.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14390000,0.98,-0.0073,-0.011,0.19,0.013,-0.0039,0.018,0.0087,-0.003,0.012,-0.0011,-0.0059,-0.00011,0.001,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00053,0.00053,0.066,0.038,0.038,0.0067,0.047,0.047,0.039,2.3e-06,2.3e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14490000,0.98,-0.0075,-0.011,0.19,0.012,-0.0036,0.021,0.0099,-0.0034,0.015,-0.0011,-0.0059,-0.00011,0.001,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00054,0.00054,0.066,0.042,0.042,0.0066,0.053,0.053,0.038,2.3e-06,2.3e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14590000,0.98,-0.0075,-0.011,0.19,0.01,-0.0036,0.019,0.0063,-0.0041,0.011,-0.0011,-0.0059,-0.00011,0.00096,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00052,0.00052,0.066,0.036,0.036,0.0065,0.046,0.046,0.038,2.2e-06,2.2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14690000,0.98,-0.0075,-0.011,0.19,0.0097,-0.0034,0.019,0.0073,-0.0044,0.011,-0.0011,-0.0059,-0.00011,0.00095,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00052,0.00052,0.066,0.04,0.04,0.0065,0.053,0.053,0.037,2.2e-06,2.2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14790000,0.98,-0.0075,-0.011,0.19,0.011,0.0023,0.019,0.0059,0.00061,0.014,-0.0011,-0.0059,-0.00011,0.0013,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00051,0.00051,0.066,0.034,0.034,0.0064,0.046,0.046,0.036,2e-06,2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14890000,0.98,-0.0074,-0.011,0.19,0.01,-8.2e-05,0.023,0.0069,0.00073,0.015,-0.0011,-0.0059,-0.00011,0.0013,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00051,0.00051,0.066,0.037,0.037,0.0064,0.052,0.052,0.036,2e-06,2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -14990000,0.98,-0.0075,-0.011,0.19,0.0093,-0.0013,0.026,0.0054,-0.00072,0.017,-0.0011,-0.0059,-0.00011,0.0012,-0.00095,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.032,0.032,0.0064,0.046,0.046,0.036,1.9e-06,1.9e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15090000,0.98,-0.0075,-0.011,0.19,0.0097,-0.00019,0.03,0.0064,-0.00084,0.019,-0.0011,-0.0059,-0.00011,0.0012,-0.00095,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.035,0.035,0.0064,0.052,0.052,0.035,1.9e-06,1.9e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15190000,0.98,-0.0076,-0.011,0.19,0.0079,-0.0013,0.03,0.0051,-0.00077,0.021,-0.0011,-0.0059,-0.00011,0.0012,-0.00082,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.031,0.03,0.0064,0.046,0.046,0.035,1.8e-06,1.8e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15290000,0.98,-0.0077,-0.011,0.19,0.0089,-0.0023,0.03,0.0059,-0.00092,0.018,-0.0011,-0.0059,-0.00011,0.0012,-0.00081,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.033,0.033,0.0065,0.052,0.052,0.035,1.8e-06,1.8e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15390000,0.98,-0.0078,-0.011,0.19,0.0091,1.3e-06,0.03,0.0048,-0.00065,0.018,-0.0011,-0.0059,-0.00011,0.0012,-0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.029,0.029,0.0064,0.045,0.045,0.034,1.7e-06,1.7e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15490000,0.98,-0.0078,-0.011,0.19,0.0089,-0.0025,0.03,0.0056,-0.00075,0.019,-0.0011,-0.0059,-0.00011,0.0012,-0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.032,0.032,0.0065,0.051,0.051,0.034,1.7e-06,1.7e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15590000,0.98,-0.0079,-0.011,0.19,0.012,-0.005,0.029,0.0071,-0.0042,0.018,-0.0011,-0.0059,-0.00011,0.00078,-0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.028,0.028,0.0065,0.045,0.045,0.034,1.6e-06,1.6e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15690000,0.98,-0.0079,-0.011,0.19,0.014,-0.008,0.03,0.0083,-0.0049,0.019,-0.0011,-0.0059,-0.00011,0.00077,-0.00071,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.03,0.03,0.0066,0.051,0.051,0.034,1.6e-06,1.6e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -15790000,0.98,-0.0079,-0.011,0.19,0.011,-0.0079,0.03,0.0066,-0.004,0.021,-0.0011,-0.0059,-0.00011,0.00094,-0.00051,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.026,0.026,0.0066,0.045,0.045,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -15890000,0.98,-0.0079,-0.011,0.19,0.0098,-0.0062,0.03,0.0076,-0.0047,0.02,-0.0011,-0.0059,-0.00011,0.00092,-0.0005,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.029,0.029,0.0067,0.05,0.05,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -15990000,0.98,-0.0078,-0.011,0.19,0.0079,-0.0052,0.027,0.0061,-0.0038,0.02,-0.0011,-0.0059,-0.00011,0.001,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.025,0.025,0.0068,0.044,0.044,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -16090000,0.98,-0.0077,-0.011,0.19,0.0076,-0.0064,0.025,0.0069,-0.0043,0.02,-0.0011,-0.0059,-0.00011,0.001,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.027,0.027,0.0069,0.05,0.05,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16190000,0.98,-0.0077,-0.011,0.19,0.0041,-0.0045,0.024,0.0044,-0.0034,0.017,-0.0011,-0.0059,-0.00011,0.0012,-1.1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.024,0.024,0.0069,0.044,0.044,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16290000,0.98,-0.0077,-0.011,0.19,0.0049,-0.006,0.024,0.0048,-0.0039,0.018,-0.0011,-0.0059,-0.00011,0.0012,-8.5e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.026,0.026,0.007,0.049,0.049,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16390000,0.98,-0.0077,-0.011,0.19,0.0065,-0.0058,0.024,0.0052,-0.0032,0.018,-0.0011,-0.0059,-0.00011,0.0013,-8.7e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.007,0.044,0.044,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16490000,0.98,-0.0078,-0.011,0.19,0.009,-0.0074,0.027,0.006,-0.0039,0.022,-0.0011,-0.0059,-0.00011,0.0013,-9.1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.025,0.025,0.0072,0.049,0.049,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16590000,0.98,-0.0078,-0.011,0.19,0.013,-0.0079,0.03,0.0052,-0.0032,0.022,-0.0011,-0.0059,-0.00011,0.0015,7.7e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.022,0.022,0.0072,0.043,0.043,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16690000,0.98,-0.0078,-0.011,0.19,0.015,-0.013,0.03,0.0066,-0.0042,0.023,-0.0011,-0.0059,-0.00011,0.0015,8.4e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.024,0.024,0.0073,0.048,0.048,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16790000,0.98,-0.0077,-0.011,0.19,0.016,-0.012,0.029,0.0055,-0.0034,0.023,-0.0012,-0.0059,-0.00011,0.0018,0.00037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.022,0.022,0.0073,0.043,0.043,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16890000,0.98,-0.0076,-0.011,0.19,0.016,-0.013,0.03,0.0071,-0.0047,0.022,-0.0012,-0.0059,-0.00011,0.0018,0.00038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.0074,0.048,0.048,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -16990000,0.98,-0.0077,-0.011,0.19,0.014,-0.013,0.03,0.0062,-0.0039,0.02,-0.0012,-0.0059,-0.00011,0.002,0.00036,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0074,0.043,0.043,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17090000,0.98,-0.0078,-0.011,0.19,0.016,-0.016,0.03,0.0077,-0.0053,0.02,-0.0012,-0.0059,-0.00011,0.002,0.00037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.0075,0.048,0.048,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17190000,0.98,-0.0079,-0.011,0.19,0.015,-0.02,0.031,0.0057,-0.0083,0.023,-0.0012,-0.0059,-0.00011,0.0019,0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.02,0.02,0.0076,0.042,0.042,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17290000,0.98,-0.0078,-0.011,0.19,0.017,-0.021,0.031,0.0073,-0.01,0.023,-0.0012,-0.0059,-0.00011,0.0019,0.00069,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.022,0.022,0.0076,0.047,0.047,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17390000,0.98,-0.0078,-0.011,0.19,0.012,-0.022,0.031,0.008,-0.0077,0.023,-0.0012,-0.0059,-0.00011,0.0026,0.00052,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.02,0.02,0.0076,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00041,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17490000,0.98,-0.0078,-0.011,0.19,0.011,-0.023,0.03,0.0091,-0.01,0.025,-0.0012,-0.0059,-0.00011,0.0026,0.00053,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0078,0.047,0.047,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00041,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.02,0.029,0.0057,-0.0083,0.022,-0.0012,-0.0059,-0.00011,0.0034,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.019,0.019,0.0077,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.0004,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17690000,0.98,-0.0078,-0.011,0.19,0.008,-0.021,0.031,0.0065,-0.01,0.025,-0.0012,-0.0059,-0.00011,0.0034,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0078,0.046,0.046,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.0004,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17790000,0.98,-0.0079,-0.011,0.19,0.0097,-0.021,0.031,0.0066,-0.0096,0.03,-0.0012,-0.0059,-0.00011,0.0041,0.001,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.0078,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00039,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17890000,0.98,-0.0078,-0.011,0.19,0.012,-0.023,0.031,0.0077,-0.012,0.034,-0.0012,-0.0059,-0.00011,0.0041,0.001,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.02,0.02,0.0079,0.046,0.046,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00039,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17990000,0.98,-0.0077,-0.011,0.19,0.012,-0.019,0.03,0.0066,-0.0071,0.035,-0.0012,-0.0059,-0.00011,0.0056,0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.018,0.018,0.0079,0.041,0.041,0.033,1e-06,1e-06,2.2e-06,0.038,0.038,0.00038,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -18090000,0.98,-0.0078,-0.011,0.19,0.012,-0.02,0.03,0.0078,-0.009,0.033,-0.0012,-0.0059,-0.00011,0.0056,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.02,0.02,0.008,0.046,0.046,0.034,1e-06,1e-06,2.2e-06,0.038,0.038,0.00038,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18190000,0.98,-0.0078,-0.011,0.19,0.011,-0.019,0.03,0.0075,-0.0077,0.031,-0.0012,-0.0059,-0.00011,0.0061,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.018,0.018,0.0079,0.041,0.041,0.034,1e-06,1e-06,2.2e-06,0.037,0.037,0.00037,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18290000,0.98,-0.0078,-0.011,0.19,0.012,-0.02,0.029,0.0087,-0.0097,0.03,-0.0012,-0.0059,-0.00011,0.0061,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.008,0.046,0.046,0.034,1e-06,1e-06,2.2e-06,0.037,0.037,0.00037,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18390000,0.98,-0.0078,-0.011,0.19,0.012,-0.019,0.029,0.0092,-0.0083,0.029,-0.0012,-0.0059,-0.00011,0.0067,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.0079,0.041,0.041,0.034,9.8e-07,9.9e-07,2.3e-06,0.037,0.037,0.00036,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18490000,0.98,-0.0078,-0.011,0.19,0.015,-0.02,0.028,0.011,-0.01,0.031,-0.0012,-0.0059,-0.00011,0.0067,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.008,0.045,0.045,0.034,9.9e-07,9.9e-07,2.3e-06,0.037,0.037,0.00036,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18590000,0.98,-0.0076,-0.011,0.19,0.014,-0.019,0.028,0.0092,-0.0088,0.033,-0.0012,-0.0059,-0.00011,0.0074,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.017,0.017,0.0079,0.041,0.041,0.034,9.5e-07,9.6e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18690000,0.98,-0.0076,-0.011,0.19,0.014,-0.019,0.026,0.011,-0.011,0.032,-0.0012,-0.0059,-0.00011,0.0074,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.019,0.019,0.008,0.045,0.045,0.034,9.6e-07,9.6e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18790000,0.98,-0.0076,-0.011,0.19,0.013,-0.018,0.026,0.0099,-0.0093,0.03,-0.0012,-0.0059,-0.00011,0.0081,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,9.3e-07,9.3e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18890000,0.98,-0.0075,-0.011,0.19,0.012,-0.019,0.024,0.011,-0.011,0.026,-0.0012,-0.0059,-0.00011,0.008,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.008,0.045,0.045,0.034,9.3e-07,9.3e-07,2.3e-06,0.037,0.037,0.00034,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -18990000,0.98,-0.0075,-0.011,0.19,0.01,-0.018,0.025,0.0095,-0.0097,0.03,-0.0012,-0.0059,-0.00011,0.0088,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,9e-07,9e-07,2.3e-06,0.036,0.036,0.00034,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19090000,0.98,-0.0076,-0.011,0.19,0.0088,-0.02,0.025,0.011,-0.012,0.026,-0.0012,-0.0059,-0.00011,0.0087,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.0079,0.045,0.045,0.035,9e-07,9e-07,2.3e-06,0.036,0.036,0.00033,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19190000,0.98,-0.0075,-0.011,0.19,0.007,-0.019,0.025,0.009,-0.01,0.025,-0.0013,-0.0059,-0.00011,0.0095,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,8.7e-07,8.7e-07,2.3e-06,0.036,0.036,0.00033,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19290000,0.98,-0.0074,-0.011,0.19,0.0066,-0.02,0.025,0.0097,-0.012,0.024,-0.0013,-0.0059,-0.00011,0.0095,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.018,0.018,0.0079,0.044,0.044,0.034,8.7e-07,8.8e-07,2.3e-06,0.036,0.036,0.00032,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19390000,0.98,-0.0075,-0.011,0.19,0.0057,-0.016,0.026,0.0084,-0.0094,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.016,0.016,0.0078,0.04,0.04,0.035,8.5e-07,8.5e-07,2.3e-06,0.036,0.036,0.00032,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19490000,0.98,-0.0075,-0.011,0.19,0.0054,-0.017,0.026,0.009,-0.011,0.023,-0.0013,-0.0059,-0.00011,0.01,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.018,0.018,0.0078,0.044,0.044,0.035,8.5e-07,8.5e-07,2.3e-06,0.036,0.036,0.00031,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19590000,0.98,-0.0075,-0.011,0.19,0.0033,-0.019,0.028,0.0084,-0.011,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0077,0.04,0.04,0.035,8.2e-07,8.2e-07,2.3e-06,0.035,0.035,0.00031,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19690000,0.98,-0.0075,-0.011,0.19,0.002,-0.018,0.026,0.0087,-0.012,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00042,0.066,0.018,0.018,0.0078,0.044,0.044,0.035,8.2e-07,8.2e-07,2.3e-06,0.035,0.035,0.0003,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -19790000,0.98,-0.0076,-0.011,0.19,0.00072,-0.016,0.025,0.0099,-0.011,0.019,-0.0013,-0.0059,-0.00011,0.011,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0077,0.04,0.04,0.035,8e-07,8e-07,2.3e-06,0.035,0.035,0.0003,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -19890000,0.98,-0.0076,-0.011,0.19,0.0011,-0.017,0.025,0.0099,-0.012,0.017,-0.0013,-0.0059,-0.00011,0.011,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.017,0.017,0.0077,0.044,0.044,0.035,8e-07,8e-07,2.3e-06,0.035,0.035,0.00029,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -19990000,0.98,-0.0076,-0.011,0.19,0.0004,-0.016,0.022,0.0093,-0.0099,0.014,-0.0013,-0.0059,-0.00011,0.012,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0076,0.04,0.04,0.035,7.7e-07,7.7e-07,2.3e-06,0.035,0.035,0.00029,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -20090000,0.98,-0.0076,-0.011,0.19,0.0013,-0.019,0.022,0.0094,-0.012,0.018,-0.0013,-0.0059,-0.00011,0.012,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.017,0.017,0.0076,0.044,0.044,0.035,7.7e-07,7.8e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20190000,0.98,-0.0076,-0.011,0.19,0.0016,-0.016,0.023,0.0097,-0.01,0.017,-0.0013,-0.0059,-0.00011,0.013,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.016,0.016,0.0075,0.039,0.039,0.035,7.5e-07,7.5e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20290000,0.98,-0.0076,-0.011,0.19,-0.0012,-0.018,0.023,0.0097,-0.012,0.018,-0.0013,-0.0059,-0.00011,0.013,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0075,0.043,0.043,0.035,7.5e-07,7.5e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20390000,0.98,-0.0076,-0.011,0.19,-0.0026,-0.016,0.024,0.0098,-0.01,0.019,-0.0013,-0.0059,-0.00011,0.014,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.016,0.016,0.0075,0.039,0.039,0.035,7.3e-07,7.3e-07,2.3e-06,0.034,0.034,0.00027,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20490000,0.98,-0.0076,-0.011,0.18,-0.007,-0.018,0.024,0.0093,-0.012,0.017,-0.0013,-0.0059,-0.00011,0.014,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0075,0.043,0.043,0.035,7.3e-07,7.3e-07,2.3e-06,0.034,0.034,0.00027,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20590000,0.98,-0.0075,-0.011,0.18,-0.0069,-0.018,0.023,0.0095,-0.01,0.016,-0.0013,-0.0059,-0.00011,0.014,0.00077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00039,0.00039,0.066,0.016,0.016,0.0074,0.039,0.039,0.035,7e-07,7.1e-07,2.3e-06,0.034,0.034,0.00026,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20690000,0.98,-0.0075,-0.011,0.18,-0.0084,-0.018,0.024,0.0087,-0.012,0.016,-0.0013,-0.0059,-0.00011,0.014,0.00078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0074,0.043,0.043,0.035,7.1e-07,7.1e-07,2.3e-06,0.034,0.034,0.00026,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20790000,0.98,-0.0069,-0.011,0.18,-0.011,-0.014,0.009,0.0072,-0.011,0.015,-0.0013,-0.0059,-0.00011,0.015,0.00054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.11,0.00039,0.00039,0.066,0.016,0.016,0.0073,0.039,0.039,0.035,6.8e-07,6.9e-07,2.3e-06,0.034,0.034,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20890000,0.98,0.0023,-0.0074,0.18,-0.017,-0.0032,-0.11,0.0057,-0.011,0.0085,-0.0013,-0.0059,-0.00011,0.015,0.00055,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.11,0.00039,0.00039,0.066,0.017,0.017,0.0073,0.043,0.043,0.035,6.8e-07,6.9e-07,2.3e-06,0.034,0.034,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20990000,0.98,0.0056,-0.0039,0.18,-0.029,0.016,-0.25,0.0041,-0.009,-0.0065,-0.0013,-0.0059,-0.00011,0.015,5.1e-05,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.093,0.00039,0.00039,0.066,0.016,0.016,0.0072,0.039,0.039,0.034,6.6e-07,6.6e-07,2.3e-06,0.033,0.033,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21090000,0.98,0.004,-0.0043,0.18,-0.042,0.031,-0.37,0.00064,-0.0066,-0.037,-0.0013,-0.0059,-0.00011,0.015,5e-05,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.063,0.00039,0.00039,0.066,0.017,0.017,0.0072,0.043,0.043,0.035,6.6e-07,6.7e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21190000,0.98,0.0012,-0.0059,0.19,-0.047,0.038,-0.49,-0.00032,-0.0049,-0.074,-0.0013,-0.0059,-0.00011,0.014,-0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.026,0.00038,0.00038,0.066,0.016,0.016,0.0071,0.039,0.039,0.035,6.4e-07,6.4e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21290000,0.98,-0.001,-0.0072,0.19,-0.047,0.04,-0.62,-0.005,-0.00096,-0.13,-0.0013,-0.0059,-0.00011,0.014,-0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.032,0.00038,0.00038,0.066,0.018,0.018,0.0071,0.043,0.043,0.035,6.4e-07,6.4e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21390000,0.98,-0.0025,-0.0079,0.19,-0.043,0.038,-0.75,-0.0049,0.0031,-0.2,-0.0013,-0.0059,-0.00011,0.014,-0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.097,0.00038,0.00038,0.066,0.016,0.016,0.007,0.039,0.039,0.035,6.2e-07,6.2e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21490000,0.98,-0.0033,-0.0083,0.19,-0.038,0.034,-0.89,-0.009,0.0067,-0.28,-0.0013,-0.0059,-0.00011,0.014,-0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.18,0.00038,0.00038,0.066,0.018,0.018,0.007,0.043,0.043,0.035,6.2e-07,6.2e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21590000,0.98,-0.0038,-0.0083,0.19,-0.03,0.031,-1,-0.0081,0.0087,-0.37,-0.0013,-0.0059,-0.00011,0.015,-0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.27,0.00037,0.00037,0.066,0.017,0.017,0.0069,0.039,0.039,0.034,6e-07,6e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21690000,0.98,-0.0041,-0.0081,0.19,-0.028,0.026,-1.1,-0.011,0.012,-0.49,-0.0013,-0.0059,-0.00011,0.014,-0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.39,0.00037,0.00037,0.066,0.018,0.018,0.0069,0.043,0.043,0.035,6e-07,6e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21790000,0.98,-0.0045,-0.0083,0.19,-0.021,0.021,-1.3,-0.0047,0.01,-0.61,-0.0013,-0.0059,-0.00011,0.015,-0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.51,0.00036,0.00036,0.066,0.017,0.017,0.0069,0.039,0.039,0.034,5.8e-07,5.8e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21890000,0.98,-0.0048,-0.0085,0.19,-0.018,0.016,-1.4,-0.0066,0.012,-0.75,-0.0013,-0.0059,-0.00011,0.015,-0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.65,0.00036,0.00036,0.066,0.018,0.018,0.0068,0.043,0.043,0.034,5.8e-07,5.8e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21990000,0.98,-0.0055,-0.0087,0.19,-0.014,0.011,-1.4,-0.0012,0.0091,-0.88,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.78,0.00036,0.00036,0.066,0.017,0.017,0.0068,0.039,0.039,0.034,5.6e-07,5.6e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22090000,0.98,-0.0062,-0.0095,0.19,-0.012,0.0068,-1.4,-0.0026,0.0099,-1,-0.0013,-0.0059,-0.00011,0.015,-0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.93,0.00036,0.00036,0.066,0.018,0.018,0.0068,0.043,0.043,0.034,5.6e-07,5.6e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22190000,0.98,-0.0067,-0.0098,0.19,-0.0041,0.002,-1.4,0.005,0.0053,-1.2,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00035,0.00035,0.066,0.016,0.016,0.0067,0.039,0.039,0.034,5.5e-07,5.4e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22290000,0.98,-0.0074,-0.01,0.19,0.00091,-0.0037,-1.4,0.0048,0.0052,-1.3,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.2,0.00035,0.00035,0.066,0.017,0.017,0.0067,0.043,0.043,0.034,5.5e-07,5.5e-07,2.3e-06,0.031,0.031,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22390000,0.98,-0.0077,-0.01,0.19,0.006,-0.012,-1.4,0.012,-0.003,-1.5,-0.0013,-0.0059,-0.00011,0.014,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00034,0.00034,0.066,0.016,0.016,0.0066,0.039,0.039,0.034,5.3e-07,5.3e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22490000,0.98,-0.0078,-0.011,0.19,0.0098,-0.018,-1.4,0.013,-0.0046,-1.6,-0.0013,-0.0059,-0.00011,0.014,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.5,0.00034,0.00034,0.066,0.017,0.017,0.0066,0.043,0.043,0.034,5.3e-07,5.3e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22590000,0.98,-0.0078,-0.011,0.19,0.019,-0.026,-1.4,0.025,-0.012,-1.7,-0.0013,-0.0059,-0.00011,0.014,-0.0044,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00034,0.00034,0.066,0.016,0.016,0.0065,0.039,0.039,0.034,5.1e-07,5.1e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22690000,0.98,-0.0077,-0.011,0.19,0.021,-0.031,-1.4,0.027,-0.015,-1.9,-0.0013,-0.0059,-0.00011,0.014,-0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.8,0.00034,0.00034,0.066,0.017,0.017,0.0065,0.043,0.043,0.034,5.1e-07,5.1e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22790000,0.98,-0.0077,-0.012,0.19,0.027,-0.038,-1.4,0.037,-0.024,-2,-0.0013,-0.0059,-0.00011,0.014,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00033,0.00033,0.066,0.015,0.015,0.0065,0.039,0.039,0.034,5e-07,5e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22890000,0.98,-0.0078,-0.012,0.19,0.03,-0.044,-1.4,0.04,-0.028,-2.2,-0.0013,-0.0059,-0.00011,0.014,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.1,0.00033,0.00033,0.066,0.016,0.016,0.0065,0.043,0.043,0.034,5e-07,5e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22990000,0.98,-0.0078,-0.013,0.18,0.035,-0.049,-1.4,0.05,-0.038,-2.3,-0.0013,-0.0059,-0.00011,0.015,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00033,0.00033,0.066,0.015,0.015,0.0064,0.039,0.039,0.034,4.8e-07,4.8e-07,2.3e-06,0.029,0.029,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23090000,0.98,-0.0078,-0.013,0.18,0.04,-0.054,-1.4,0.054,-0.043,-2.5,-0.0013,-0.0059,-0.00011,0.014,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.4,0.00033,0.00033,0.066,0.016,0.016,0.0064,0.043,0.043,0.034,4.8e-07,4.8e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23190000,0.98,-0.0078,-0.013,0.18,0.046,-0.055,-1.4,0.065,-0.052,-2.6,-0.0013,-0.0059,-0.00011,0.015,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00032,0.00032,0.066,0.015,0.015,0.0063,0.039,0.039,0.033,4.7e-07,4.7e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23290000,0.98,-0.0083,-0.013,0.18,0.051,-0.06,-1.4,0.07,-0.058,-2.8,-0.0013,-0.0059,-0.00011,0.015,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.7,0.00032,0.00032,0.066,0.016,0.016,0.0063,0.043,0.043,0.034,4.7e-07,4.7e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23390000,0.98,-0.0082,-0.013,0.18,0.057,-0.062,-1.4,0.081,-0.063,-2.9,-0.0013,-0.0059,-0.00011,0.016,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00032,0.00032,0.066,0.015,0.015,0.0063,0.039,0.039,0.033,4.6e-07,4.6e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23490000,0.98,-0.0083,-0.014,0.18,0.061,-0.065,-1.4,0.087,-0.069,-3,-0.0013,-0.0059,-0.00011,0.016,-0.0034,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.9,0.00032,0.00032,0.066,0.016,0.016,0.0063,0.043,0.043,0.033,4.6e-07,4.6e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23590000,0.98,-0.0085,-0.014,0.18,0.064,-0.067,-1.4,0.095,-0.078,-3.2,-0.0013,-0.0059,-0.00011,0.017,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00031,0.00031,0.066,0.014,0.014,0.0062,0.039,0.039,0.033,4.5e-07,4.5e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23690000,0.98,-0.0091,-0.014,0.18,0.062,-0.07,-1.3,0.1,-0.085,-3.3,-0.0013,-0.0059,-0.00011,0.017,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.2,0.00031,0.00031,0.066,0.015,0.015,0.0062,0.042,0.042,0.033,4.5e-07,4.5e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23790000,0.98,-0.011,-0.017,0.18,0.057,-0.067,-0.95,0.11,-0.089,-3.4,-0.0013,-0.0059,-0.00011,0.018,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.3,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.038,0.038,0.033,4.4e-07,4.4e-07,2.3e-06,0.028,0.028,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23890000,0.98,-0.014,-0.021,0.18,0.052,-0.068,-0.52,0.12,-0.096,-3.5,-0.0013,-0.0059,-0.00011,0.018,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.042,0.042,0.033,4.4e-07,4.4e-07,2.3e-06,0.028,0.028,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23990000,0.98,-0.016,-0.024,0.18,0.054,-0.066,-0.13,0.13,-0.097,-3.6,-0.0013,-0.0059,-0.00011,0.02,-0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.013,0.013,0.0061,0.038,0.038,0.033,4.3e-07,4.3e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24090000,0.98,-0.016,-0.023,0.18,0.06,-0.075,0.099,0.13,-0.1,-3.6,-0.0013,-0.0059,-0.00011,0.02,-0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.042,0.042,0.033,4.3e-07,4.3e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24190000,0.98,-0.013,-0.019,0.18,0.071,-0.08,0.089,0.14,-0.11,-3.6,-0.0013,-0.0059,-0.00011,0.021,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.013,0.013,0.006,0.038,0.038,0.033,4.2e-07,4.2e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24290000,0.98,-0.011,-0.016,0.18,0.075,-0.084,0.067,0.15,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.021,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.014,0.014,0.006,0.042,0.042,0.033,4.2e-07,4.2e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24390000,0.98,-0.0099,-0.015,0.18,0.069,-0.078,0.083,0.15,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.023,-0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.013,0.013,0.006,0.038,0.038,0.033,4.1e-07,4.1e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24490000,0.98,-0.01,-0.015,0.18,0.064,-0.076,0.081,0.16,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.023,-0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.014,0.014,0.006,0.041,0.041,0.033,4.1e-07,4.1e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24590000,0.98,-0.011,-0.015,0.19,0.061,-0.072,0.077,0.16,-0.12,-3.6,-0.0014,-0.0059,-0.00011,0.024,-0.0058,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.013,0.013,0.0059,0.038,0.038,0.033,4e-07,4e-07,2.3e-06,0.028,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24690000,0.98,-0.011,-0.015,0.19,0.059,-0.072,0.076,0.17,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.024,-0.0058,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0059,0.041,0.041,0.033,4e-07,4e-07,2.3e-06,0.028,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24790000,0.98,-0.011,-0.014,0.19,0.056,-0.069,0.068,0.17,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.026,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.013,0.013,0.0059,0.038,0.038,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24890000,0.98,-0.011,-0.014,0.19,0.054,-0.073,0.057,0.18,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.026,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0059,0.041,0.041,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24990000,0.98,-0.011,-0.014,0.19,0.045,-0.069,0.05,0.18,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.029,-0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.013,0.013,0.0058,0.037,0.037,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25090000,0.98,-0.011,-0.014,0.19,0.042,-0.068,0.048,0.18,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.029,-0.0077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0058,0.041,0.041,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25190000,0.98,-0.011,-0.014,0.19,0.037,-0.062,0.048,0.18,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.031,-0.0089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0058,0.037,0.037,0.032,3.8e-07,3.8e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25290000,0.98,-0.012,-0.013,0.19,0.032,-0.064,0.042,0.19,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.031,-0.0088,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0058,0.041,0.041,0.032,3.8e-07,3.8e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25390000,0.98,-0.012,-0.013,0.19,0.024,-0.056,0.041,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.0001,0.033,-0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0058,0.037,0.037,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25490000,0.98,-0.012,-0.013,0.19,0.019,-0.057,0.041,0.18,-0.12,-3.5,-0.0014,-0.0058,-0.0001,0.033,-0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0058,0.041,0.041,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25590000,0.98,-0.012,-0.013,0.19,0.014,-0.052,0.042,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.0001,0.035,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.6e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25690000,0.98,-0.011,-0.012,0.19,0.013,-0.052,0.031,0.18,-0.12,-3.5,-0.0014,-0.0058,-0.0001,0.035,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25790000,0.98,-0.011,-0.012,0.19,0.0025,-0.043,0.031,0.17,-0.1,-3.5,-0.0015,-0.0058,-0.0001,0.037,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.6e-07,3.6e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25890000,0.98,-0.011,-0.012,0.19,-0.0031,-0.042,0.033,0.17,-0.11,-3.5,-0.0015,-0.0058,-0.0001,0.037,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.6e-07,3.6e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25990000,0.98,-0.011,-0.012,0.19,-0.012,-0.034,0.027,0.16,-0.098,-3.5,-0.0015,-0.0058,-0.0001,0.039,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26090000,0.98,-0.011,-0.012,0.19,-0.017,-0.035,0.025,0.16,-0.1,-3.5,-0.0015,-0.0058,-0.0001,0.039,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26190000,0.98,-0.011,-0.012,0.19,-0.023,-0.027,0.021,0.15,-0.093,-3.5,-0.0015,-0.0058,-0.0001,0.04,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26290000,0.98,-0.011,-0.013,0.19,-0.024,-0.027,0.015,0.15,-0.096,-3.5,-0.0015,-0.0058,-0.0001,0.04,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26390000,0.98,-0.01,-0.013,0.19,-0.03,-0.019,0.019,0.14,-0.086,-3.5,-0.0015,-0.0058,-0.0001,0.041,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26490000,0.98,-0.0099,-0.013,0.19,-0.033,-0.016,0.028,0.13,-0.088,-3.5,-0.0015,-0.0058,-0.0001,0.041,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26590000,0.98,-0.0093,-0.013,0.19,-0.035,-0.0072,0.029,0.12,-0.08,-3.5,-0.0015,-0.0058,-0.0001,0.042,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26690000,0.98,-0.0091,-0.013,0.19,-0.037,-0.0027,0.027,0.12,-0.08,-3.5,-0.0015,-0.0058,-0.0001,0.042,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26790000,0.98,-0.0089,-0.012,0.19,-0.044,0.0018,0.027,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26890000,0.98,-0.0083,-0.012,0.19,-0.049,0.0045,0.022,0.1,-0.073,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26990000,0.98,-0.0077,-0.013,0.19,-0.056,0.012,0.021,0.089,-0.065,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27090000,0.98,-0.0076,-0.013,0.19,-0.058,0.019,0.025,0.084,-0.064,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0055,0.041,0.041,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27190000,0.98,-0.0076,-0.013,0.19,-0.064,0.025,0.027,0.073,-0.056,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27290000,0.98,-0.0078,-0.014,0.19,-0.071,0.03,0.14,0.066,-0.053,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.014,0.014,0.0055,0.041,0.041,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.026,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27390000,0.98,-0.0092,-0.016,0.18,-0.077,0.037,0.46,0.056,-0.045,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27490000,0.98,-0.011,-0.018,0.18,-0.081,0.042,0.78,0.048,-0.041,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.014,0.013,0.0055,0.04,0.04,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27590000,0.98,-0.01,-0.017,0.18,-0.076,0.046,0.87,0.04,-0.035,-3.4,-0.0015,-0.0058,-0.0001,0.044,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.3,0.00029,0.00029,0.065,0.013,0.012,0.0055,0.037,0.037,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27690000,0.98,-0.0092,-0.014,0.18,-0.072,0.042,0.78,0.032,-0.03,-3.3,-0.0015,-0.0058,-0.0001,0.044,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.2,0.00029,0.00029,0.065,0.014,0.013,0.0055,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27790000,0.98,-0.0079,-0.013,0.18,-0.071,0.04,0.77,0.026,-0.027,-3.2,-0.0015,-0.0058,-0.0001,0.043,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00029,0.00029,0.065,0.013,0.012,0.0054,0.037,0.037,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27890000,0.98,-0.0075,-0.013,0.18,-0.078,0.047,0.81,0.018,-0.022,-3.2,-0.0015,-0.0058,-0.0001,0.043,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00029,0.00029,0.065,0.014,0.013,0.0054,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27990000,0.98,-0.008,-0.013,0.18,-0.078,0.049,0.8,0.013,-0.019,-3.1,-0.0015,-0.0058,-0.0001,0.042,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3,0.00029,0.00029,0.065,0.013,0.012,0.0054,0.037,0.037,0.031,3.1e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28090000,0.98,-0.0083,-0.013,0.18,-0.081,0.05,0.8,0.0049,-0.014,-3,-0.0015,-0.0058,-0.0001,0.042,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.9,0.00029,0.00029,0.065,0.014,0.013,0.0054,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28190000,0.98,-0.0078,-0.013,0.18,-0.082,0.047,0.81,-0.0019,-0.012,-2.9,-0.0015,-0.0058,-0.0001,0.041,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28290000,0.98,-0.0073,-0.014,0.18,-0.087,0.05,0.81,-0.01,-0.0074,-2.9,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28390000,0.98,-0.0073,-0.014,0.18,-0.087,0.054,0.81,-0.015,-0.0032,-2.8,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.7,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28490000,0.98,-0.0076,-0.015,0.18,-0.089,0.058,0.81,-0.024,0.0024,-2.7,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.6,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28590000,0.98,-0.0077,-0.015,0.18,-0.082,0.053,0.81,-0.027,0.0014,-2.6,-0.0015,-0.0058,-0.0001,0.039,-0.016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,2.9e-07,2.4e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28690000,0.98,-0.0075,-0.014,0.18,-0.082,0.054,0.81,-0.036,0.0069,-2.6,-0.0015,-0.0058,-0.0001,0.039,-0.016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28790000,0.98,-0.0068,-0.014,0.18,-0.079,0.055,0.81,-0.038,0.0098,-2.5,-0.0014,-0.0058,-9.9e-05,0.039,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.4,0.00029,0.00029,0.064,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28890000,0.98,-0.0067,-0.013,0.18,-0.083,0.056,0.81,-0.046,0.015,-2.4,-0.0014,-0.0058,-9.9e-05,0.039,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.3,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28990000,0.98,-0.0065,-0.014,0.18,-0.079,0.054,0.81,-0.046,0.016,-2.3,-0.0014,-0.0058,-9.9e-05,0.037,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00029,0.00029,0.064,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29090000,0.98,-0.0064,-0.014,0.18,-0.081,0.056,0.81,-0.054,0.021,-2.3,-0.0014,-0.0058,-9.9e-05,0.038,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00029,0.00029,0.064,0.013,0.013,0.0053,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29190000,0.98,-0.0064,-0.014,0.18,-0.077,0.055,0.8,-0.051,0.021,-2.2,-0.0014,-0.0058,-9.8e-05,0.036,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.1,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29290000,0.98,-0.0067,-0.014,0.18,-0.079,0.061,0.81,-0.059,0.027,-2.1,-0.0014,-0.0058,-9.8e-05,0.037,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2,0.00029,0.00029,0.063,0.014,0.013,0.0053,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29390000,0.98,-0.0072,-0.013,0.18,-0.074,0.06,0.81,-0.058,0.029,-2,-0.0014,-0.0058,-9.7e-05,0.036,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29490000,0.98,-0.0072,-0.013,0.18,-0.077,0.06,0.81,-0.065,0.035,-2,-0.0014,-0.0058,-9.7e-05,0.036,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29590000,0.98,-0.0071,-0.013,0.18,-0.073,0.058,0.81,-0.063,0.035,-1.9,-0.0014,-0.0058,-9.7e-05,0.035,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.8,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29690000,0.98,-0.0072,-0.013,0.18,-0.077,0.057,0.81,-0.07,0.041,-1.8,-0.0014,-0.0058,-9.7e-05,0.035,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.7,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29790000,0.98,-0.0071,-0.013,0.18,-0.073,0.051,0.8,-0.065,0.039,-1.7,-0.0014,-0.0058,-9.6e-05,0.034,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00029,0.00029,0.063,0.012,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29890000,0.98,-0.0065,-0.014,0.18,-0.073,0.052,0.8,-0.073,0.044,-1.7,-0.0014,-0.0058,-9.6e-05,0.034,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29990000,0.98,-0.0068,-0.014,0.18,-0.068,0.047,0.8,-0.068,0.04,-1.6,-0.0014,-0.0058,-9.6e-05,0.033,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.5,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.8e-07,2.8e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30090000,0.98,-0.0069,-0.014,0.18,-0.068,0.048,0.8,-0.075,0.045,-1.5,-0.0014,-0.0058,-9.6e-05,0.033,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.8e-07,2.8e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30190000,0.98,-0.0069,-0.014,0.18,-0.062,0.045,0.8,-0.068,0.044,-1.5,-0.0014,-0.0058,-9.5e-05,0.032,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.031,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30290000,0.98,-0.007,-0.014,0.18,-0.061,0.045,0.8,-0.075,0.048,-1.4,-0.0014,-0.0058,-9.5e-05,0.032,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.3,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30390000,0.98,-0.007,-0.014,0.18,-0.054,0.039,0.8,-0.066,0.046,-1.3,-0.0014,-0.0057,-9.4e-05,0.032,-0.027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.2,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30490000,0.98,-0.007,-0.014,0.18,-0.057,0.039,0.8,-0.072,0.05,-1.2,-0.0014,-0.0057,-9.4e-05,0.032,-0.027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.031,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30590000,0.98,-0.0074,-0.014,0.18,-0.052,0.036,0.8,-0.065,0.046,-1.2,-0.0014,-0.0057,-9.4e-05,0.031,-0.028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30690000,0.98,-0.0078,-0.014,0.18,-0.05,0.035,0.8,-0.07,0.05,-1.1,-0.0014,-0.0057,-9.4e-05,0.031,-0.028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30790000,0.98,-0.0075,-0.014,0.18,-0.043,0.03,0.8,-0.063,0.049,-1,-0.0013,-0.0057,-9.3e-05,0.031,-0.029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.92,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30890000,0.98,-0.0069,-0.014,0.18,-0.044,0.026,0.79,-0.067,0.052,-0.95,-0.0013,-0.0057,-9.3e-05,0.031,-0.03,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.85,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30990000,0.98,-0.0071,-0.014,0.18,-0.036,0.021,0.79,-0.057,0.045,-0.88,-0.0013,-0.0057,-9.3e-05,0.03,-0.031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.78,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31090000,0.98,-0.0073,-0.014,0.18,-0.035,0.02,0.79,-0.061,0.047,-0.81,-0.0013,-0.0057,-9.3e-05,0.03,-0.031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.71,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31190000,0.98,-0.0075,-0.014,0.18,-0.03,0.015,0.8,-0.052,0.042,-0.74,-0.0013,-0.0057,-9.3e-05,0.03,-0.032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.64,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31290000,0.98,-0.0078,-0.014,0.18,-0.028,0.013,0.8,-0.055,0.044,-0.67,-0.0013,-0.0057,-9.3e-05,0.03,-0.032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.57,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31390000,0.98,-0.0076,-0.014,0.18,-0.022,0.0066,0.8,-0.047,0.039,-0.59,-0.0013,-0.0057,-9.2e-05,0.03,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.49,0.00029,0.00029,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31490000,0.98,-0.0073,-0.014,0.18,-0.022,0.0035,0.8,-0.049,0.039,-0.52,-0.0013,-0.0057,-9.2e-05,0.03,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.42,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31590000,0.98,-0.0072,-0.015,0.18,-0.018,0.0016,0.8,-0.038,0.035,-0.45,-0.0013,-0.0057,-9.2e-05,0.03,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.35,0.00028,0.00029,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31690000,0.98,-0.0072,-0.015,0.18,-0.02,0.00032,0.8,-0.04,0.035,-0.38,-0.0013,-0.0057,-9.2e-05,0.03,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.28,0.00029,0.00029,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31790000,0.98,-0.0075,-0.016,0.18,-0.011,-0.0021,0.8,-0.029,0.034,-0.3,-0.0013,-0.0057,-9.2e-05,0.031,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.2,0.00028,0.00028,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31890000,0.98,-0.0072,-0.016,0.18,-0.008,-0.0047,0.8,-0.029,0.034,-0.24,-0.0013,-0.0057,-9.2e-05,0.031,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.14,0.00028,0.00028,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31990000,0.98,-0.0075,-0.015,0.18,-0.00019,-0.0051,0.79,-0.018,0.031,-0.17,-0.0013,-0.0057,-9.2e-05,0.031,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.068,0.00028,0.00028,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32090000,0.98,-0.0079,-0.015,0.18,-0.00077,-0.0087,0.8,-0.018,0.03,-0.096,-0.0013,-0.0057,-9.2e-05,0.031,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.004,0.00028,0.00028,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32190000,0.98,-0.0081,-0.015,0.18,0.0045,-0.012,0.8,-0.0066,0.029,-0.028,-0.0013,-0.0057,-9.1e-05,0.032,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.072,0.00028,0.00028,0.062,0.012,0.012,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32290000,0.98,-0.008,-0.015,0.18,0.006,-0.015,0.8,-0.0061,0.028,0.042,-0.0013,-0.0057,-9.1e-05,0.032,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00028,0.00028,0.062,0.013,0.013,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32390000,0.98,-0.0082,-0.015,0.18,0.012,-0.016,0.79,0.0052,0.026,0.12,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.22,0.00028,0.00028,0.062,0.012,0.012,0.0051,0.036,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32490000,0.98,-0.011,-0.013,0.18,0.039,-0.082,-0.077,0.0084,0.019,0.12,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.22,0.00028,0.00028,0.062,0.015,0.015,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32590000,0.98,-0.011,-0.013,0.18,0.04,-0.083,-0.08,0.02,0.016,0.1,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.2,0.00028,0.00028,0.062,0.014,0.014,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32690000,0.98,-0.011,-0.013,0.18,0.036,-0.088,-0.081,0.024,0.007,0.088,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.19,0.00028,0.00028,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32790000,0.98,-0.011,-0.013,0.18,0.035,-0.087,-0.082,0.034,0.0051,0.072,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.17,0.00028,0.00027,0.062,0.014,0.013,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32890000,0.98,-0.011,-0.013,0.18,0.035,-0.094,-0.084,0.037,-0.0039,0.058,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.16,0.00028,0.00028,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32990000,0.98,-0.011,-0.013,0.18,0.033,-0.093,-0.083,0.045,-0.0074,0.044,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00027,0.00027,0.062,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33090000,0.98,-0.011,-0.013,0.18,0.03,-0.097,-0.08,0.049,-0.017,0.037,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00027,0.00027,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33190000,0.98,-0.011,-0.013,0.18,0.027,-0.097,-0.079,0.055,-0.019,0.029,-0.0014,-0.0057,-9.1e-05,0.034,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.13,0.00027,0.00027,0.061,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33290000,0.98,-0.011,-0.013,0.18,0.024,-0.1,-0.079,0.057,-0.029,0.021,-0.0014,-0.0057,-9.1e-05,0.034,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33390000,0.98,-0.011,-0.014,0.18,0.021,-0.094,-0.077,0.061,-0.026,0.012,-0.0014,-0.0057,-9.1e-05,0.035,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.033 -33490000,0.98,-0.01,-0.013,0.18,0.017,-0.097,-0.076,0.063,-0.036,0.0025,-0.0014,-0.0057,-9.1e-05,0.035,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.058 -33590000,0.98,-0.01,-0.014,0.18,0.014,-0.096,-0.073,0.065,-0.033,-0.0054,-0.0014,-0.0057,-9e-05,0.037,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.013,0.005,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.083 -33690000,0.98,-0.01,-0.014,0.18,0.01,-0.099,-0.074,0.066,-0.043,-0.013,-0.0014,-0.0057,-9e-05,0.037,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.11 -33790000,0.98,-0.01,-0.014,0.18,0.0061,-0.096,-0.069,0.07,-0.04,-0.02,-0.0014,-0.0057,-9e-05,0.039,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.061,0.013,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.13 -33890000,0.98,-0.01,-0.014,0.18,0.0027,-0.098,-0.068,0.07,-0.049,-0.027,-0.0014,-0.0057,-9e-05,0.039,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.061,0.014,0.014,0.0051,0.041,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.16 -33990000,0.98,-0.01,-0.014,0.18,0.00041,-0.092,-0.065,0.072,-0.044,-0.031,-0.0014,-0.0056,-9e-05,0.04,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.18 -34090000,0.98,-0.01,-0.014,0.18,-0.0035,-0.097,-0.063,0.072,-0.053,-0.035,-0.0014,-0.0056,-9e-05,0.04,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.014,0.0051,0.041,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.21 -34190000,0.98,-0.0099,-0.014,0.18,-0.0066,-0.092,-0.06,0.074,-0.047,-0.039,-0.0014,-0.0056,-9e-05,0.042,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.23 -34290000,0.98,-0.0097,-0.014,0.18,-0.0069,-0.096,-0.059,0.073,-0.057,-0.044,-0.0014,-0.0056,-9e-05,0.042,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.041,0.04,0.03,2.4e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.26 -34390000,0.98,-0.0096,-0.014,0.18,-0.01,-0.09,-0.054,0.074,-0.051,-0.049,-0.0014,-0.0056,-8.9e-05,0.043,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.28 -34490000,0.98,-0.0096,-0.014,0.18,-0.013,-0.094,-0.053,0.072,-0.06,-0.051,-0.0014,-0.0056,-8.9e-05,0.043,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.041,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.31 -34590000,0.98,-0.0095,-0.014,0.18,-0.017,-0.085,0.74,0.073,-0.054,-0.023,-0.0014,-0.0056,-8.9e-05,0.045,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.012,0.012,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.33 -34690000,0.98,-0.0095,-0.013,0.18,-0.022,-0.084,1.7,0.071,-0.062,0.096,-0.0014,-0.0056,-8.9e-05,0.045,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.012,0.0051,0.04,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.36 -34790000,0.98,-0.0094,-0.013,0.18,-0.027,-0.074,2.7,0.071,-0.056,0.28,-0.0014,-0.0056,-8.8e-05,0.047,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.012,0.012,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.3e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -34890000,0.98,-0.0094,-0.013,0.18,-0.033,-0.073,3.7,0.068,-0.063,0.57,-0.0014,-0.0056,-8.8e-05,0.047,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.04,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.3e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +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.00053,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.00083,0.0071,0.0016,0.00011,-0.023,-0.0011,-0.0057,-0.00011,-0.00035,0.00028,-0.14,0.2,-3e-06,0.43,-0.00016,-6e-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.00052,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.00035,0.013,-0.0011,-0.0055,-0.021,-0.0012,-0.0056,-0.00011,-0.00031,0.00026,-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.00051,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.00028,0.00019,-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.0005,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.00017,8.6e-05,-0.14,0.2,-3.2e-06,0.43,-0.00026,1.2e-05,-9e-05,0,0,0.095,0.002,0.0014,0.041,0.09,0.094,0.17,0.09,0.09,0.062,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00049,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.01,0.00021,-0.0052,-0.018,-0.0012,-0.0055,-0.00011,-6.9e-05,0.00021,-0.14,0.2,-4.1e-06,0.43,-0.00033,-3.1e-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.00049,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.00022,0.00016,-0.14,0.2,-4.1e-06,0.43,-0.00026,-6e-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.00048,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.02,0.00071,-0.0039,-0.0075,-0.0011,-0.0056,-0.00011,-0.00031,-4.4e-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.00048,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.00043,-0.001,-0.0056,-0.00012,-0.00044,2e-06,-0.14,0.2,-2.4e-06,0.43,-0.00017,-2e-06,-0.00012,0,0,0.095,0.0017,0.0013,0.04,0.066,0.075,0.083,0.062,0.062,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00047,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.00033,0.026,0.0016,-0.0032,-0.00019,-0.001,-0.0057,-0.00012,-0.00054,0.00012,-0.14,0.2,-2.2e-06,0.43,-0.0001,-4.1e-05,-0.00015,0,0,0.095,0.0017,0.0012,0.04,0.074,0.088,0.077,0.067,0.068,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00047,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.00078,0.016,0.0009,-0.0025,-0.0086,-0.001,-0.0057,-0.00012,-0.00056,3e-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.062,0.056,0.056,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00047,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.00073,0.02,0.0016,-0.0025,-0.0025,-0.001,-0.0057,-0.00012,-0.00054,-5.2e-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.057,0.061,0.062,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00047,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.00077,-0.002,-0.0036,-0.001,-0.0058,-0.00012,-0.00063,4.1e-05,-0.14,0.2,-2.3e-06,0.43,-5.1e-05,-7e-05,-0.00019,0,0,0.095,0.0014,0.0011,0.04,0.06,0.072,0.048,0.052,0.052,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00047,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.0018,0.018,0.00093,-0.0018,-0.005,-0.0011,-0.0058,-0.00012,-0.00059,0.00016,-0.14,0.2,-2.5e-06,0.43,-4.5e-05,-8.6e-05,-0.00022,0,0,0.095,0.0014,0.001,0.04,0.068,0.084,0.044,0.058,0.059,0.066,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00047,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.002,-0.0011,-0.0058,-0.00012,-6.6e-05,0.00012,-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.037,0.049,0.05,0.063,1.2e-05,9.4e-06,2.2e-06,0.039,0.039,0.00047,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.0013,0.017,0.0003,-0.0026,-0.0013,-0.0011,-0.0058,-0.00012,-0.00027,0.00028,-0.14,0.2,-2.4e-06,0.43,-2.7e-05,-9.2e-05,-0.00026,0,0,0.095,0.0012,0.00095,0.039,0.066,0.082,0.034,0.056,0.057,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00047,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.0035,0.015,0.0014,-0.0027,-0.005,-0.0011,-0.0058,-0.00012,-0.00034,0.00044,-0.14,0.2,-2.7e-06,0.43,-4.5e-05,-9.9e-05,-0.00026,0,0,0.095,0.0011,0.00088,0.039,0.056,0.068,0.03,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00047,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.018,0.0028,-0.0029,0.0011,-0.001,-0.0058,-0.00012,-0.00053,0.00019,-0.14,0.2,-2.4e-06,0.43,-4.4e-05,-6.6e-05,-0.00025,0,0,0.095,0.0011,0.00088,0.039,0.064,0.079,0.027,0.054,0.056,0.06,9.9e-06,7.6e-06,2.2e-06,0.039,0.039,0.00047,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.017,0.0025,-0.0017,0.0029,-0.001,-0.0058,-0.00012,-0.0012,-0.00046,-0.14,0.2,-2.3e-06,0.43,-7.3e-06,-3.1e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.055,0.065,0.024,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00047,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.016,0.0032,-0.0024,0.0039,-0.001,-0.0058,-0.00013,-0.0015,-0.00029,-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.022,0.053,0.055,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00047,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.014,0.0027,-0.0021,-0.0021,-0.001,-0.0058,-0.00013,-0.0018,-0.00077,-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.02,0.046,0.047,0.056,6.8e-06,5.5e-06,2.2e-06,0.039,0.038,0.00047,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.0097,-0.0064,0.018,0.0041,-0.0031,-6.2e-05,-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.018,0.053,0.055,0.055,6.7e-06,5.4e-06,2.1e-06,0.039,0.038,0.00047,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.02,0.0043,-0.0042,0.0017,-0.00098,-0.0058,-0.00013,-0.0023,-0.00089,-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.017,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00047,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.019,0.0054,-0.0056,0.0033,-0.00097,-0.0058,-0.00013,-0.0025,-0.00083,-0.14,0.2,-1.8e-06,0.43,7.8e-05,1.6e-05,-0.00033,0,0,0.095,0.00077,0.00069,0.039,0.057,0.067,0.015,0.053,0.054,0.053,5.6e-06,4.6e-06,2.1e-06,0.039,0.038,0.00047,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.021,0.0054,-0.0062,0.0054,-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.014,0.046,0.047,0.051,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00047,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.022,0.0071,-0.007,0.0085,-0.00099,-0.0058,-0.00012,-0.0014,-0.0015,-0.14,0.2,-1.9e-06,0.43,2.4e-05,4.4e-05,-0.00029,0,0,0.095,0.0007,0.00065,0.039,0.055,0.063,0.013,0.052,0.054,0.051,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00047,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.022,0.005,-0.0047,0.0096,-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.012,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00047,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.02,0.0067,-0.0048,0.0085,-0.001,-0.0058,-0.00012,-0.00078,-0.0018,-0.14,0.2,-2.5e-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.011,0.052,0.054,0.049,4.1e-06,3.4e-06,2.1e-06,0.038,0.037,0.00047,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.019,0.003,-0.0048,0.0091,-0.0011,-0.0058,-0.00012,-0.00056,-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.011,0.045,0.047,0.047,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13290000,0.98,-0.0079,-0.012,0.18,0.011,-0.0095,0.016,0.0046,-0.0059,0.0085,-0.001,-0.0058,-0.00012,-0.00078,-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.055,0.01,0.052,0.054,0.047,3.5e-06,3e-06,2.1e-06,0.038,0.037,0.00047,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.016,0.0032,-0.0049,0.0091,-0.0011,-0.0058,-0.00012,-0.0015,-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.0094,0.045,0.046,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00047,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.015,0.0048,-0.0056,0.0053,-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.009,0.052,0.053,0.045,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00047,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.017,0.0065,-0.0048,0.0038,-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.0085,0.045,0.046,0.044,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00047,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.017,0.0077,-0.0052,0.0064,-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.0082,0.052,0.053,0.044,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00047,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.0043,0.017,0.0098,-0.0027,0.0059,-0.0011,-0.0058,-0.00013,-0.0022,-0.0025,-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.0078,0.045,0.046,0.042,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00047,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.018,0.011,-0.0025,0.0082,-0.0011,-0.0058,-0.00012,-0.0016,-0.002,-0.14,0.2,-3e-06,0.43,6.2e-05,-2.3e-08,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.042,0.046,0.0076,0.051,0.053,0.042,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00047,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.00099,0.017,0.0088,-0.003,0.0071,-0.0011,-0.0058,-0.00012,-0.001,-0.0024,-0.14,0.2,-2.9e-06,0.43,7e-05,-1.3e-06,-0.00031,0,0,0.095,0.0005,0.0005,0.038,0.036,0.039,0.0073,0.045,0.046,0.041,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00047,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.018,0.011,-0.0049,0.0035,-0.0011,-0.0058,-0.00013,-0.0028,-0.0022,-0.14,0.2,-2.8e-06,0.43,0.00012,6.8e-06,-0.00035,0,0,0.095,0.0005,0.0005,0.038,0.04,0.043,0.0072,0.051,0.053,0.041,2.2e-06,2e-06,2.1e-06,0.037,0.036,0.00047,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.018,0.01,-0.0045,0.0037,-0.001,-0.0058,-0.00014,-0.004,-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.007,0.045,0.046,0.04,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00046,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.016,0.012,-0.0054,0.008,-0.001,-0.0058,-0.00014,-0.0041,-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.0069,0.051,0.052,0.039,2e-06,1.8e-06,2.1e-06,0.037,0.036,0.00046,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.018,0.011,-0.0054,0.012,-0.001,-0.0058,-0.00014,-0.0039,-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.0067,0.045,0.046,0.039,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00046,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.021,0.013,-0.0073,0.015,-0.001,-0.0058,-0.00014,-0.0049,-0.0045,-0.14,0.2,-2.3e-06,0.43,0.00022,4.9e-05,-0.00037,0,0,0.095,0.00047,0.00047,0.038,0.036,0.038,0.0066,0.051,0.052,0.038,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00046,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.019,0.0099,-0.0073,0.011,-0.001,-0.0058,-0.00015,-0.0055,-0.0058,-0.14,0.2,-2.1e-06,0.43,0.00027,6.8e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.031,0.033,0.0065,0.045,0.045,0.038,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00046,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.019,0.012,-0.0083,0.011,-0.001,-0.0058,-0.00014,-0.0054,-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.0065,0.05,0.051,0.037,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00046,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.0033,0.019,0.01,-0.0022,0.014,-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.0064,0.044,0.045,0.036,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00046,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.0054,0.023,0.013,-0.0023,0.015,-0.0011,-0.0058,-0.00013,-0.0043,-0.0092,-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.0064,0.05,0.051,0.036,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00046,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.026,0.012,-0.0029,0.017,-0.0011,-0.0058,-0.00013,-0.0042,-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.0064,0.044,0.045,0.036,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00046,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.03,0.014,-0.0036,0.019,-0.0011,-0.0058,-0.00013,-0.0043,-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.0064,0.05,0.051,0.035,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00046,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.0058,0.03,0.012,-0.0032,0.021,-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.0064,0.044,0.045,0.035,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.00046,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.03,0.015,-0.0034,0.018,-0.0011,-0.0058,-0.00013,-0.0043,-0.014,-0.14,0.2,-1.2e-06,0.43,0.00034,0.00017,-0.00027,0,0,0.095,0.00043,0.00044,0.038,0.029,0.031,0.0065,0.049,0.05,0.035,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.00046,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.03,0.012,-0.0028,0.018,-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.025,0.027,0.0064,0.044,0.044,0.034,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.00046,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.03,0.014,-0.0034,0.019,-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,0.095,0.00042,0.00043,0.038,0.028,0.029,0.0065,0.049,0.05,0.034,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00046,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.029,0.014,-0.0059,0.018,-0.0011,-0.0058,-0.00013,-0.0043,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00028,0,0,0.095,0.00041,0.00043,0.038,0.024,0.026,0.0065,0.043,0.044,0.034,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00046,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.03,0.015,-0.0063,0.019,-0.0011,-0.0058,-0.00012,-0.0033,-0.012,-0.14,0.2,-1.8e-06,0.43,0.00032,0.00013,-0.00026,0,0,0.095,0.00041,0.00043,0.038,0.026,0.028,0.0066,0.049,0.049,0.034,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00045,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.03,0.012,-0.0047,0.021,-0.0011,-0.0058,-0.00012,-0.0021,-0.011,-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.0066,0.043,0.044,0.033,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00045,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.03,0.015,-0.0061,0.02,-0.0011,-0.0058,-0.00012,-0.0032,-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.0067,0.048,0.049,0.034,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00045,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.027,0.013,-0.0051,0.02,-0.0011,-0.0058,-0.00012,-0.0035,-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.0068,0.043,0.043,0.033,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00045,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.025,0.015,-0.0062,0.02,-0.0011,-0.0058,-0.00013,-0.0041,-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.0069,0.048,0.049,0.033,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00045,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.024,0.011,-0.0054,0.016,-0.0011,-0.0058,-0.00013,-0.0048,-0.015,-0.14,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.0069,0.043,0.043,0.033,1.2e-06,1e-06,2e-06,0.036,0.033,0.00044,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.024,0.013,-0.0061,0.018,-0.0011,-0.0058,-0.00013,-0.0045,-0.014,-0.14,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.007,0.047,0.048,0.033,1.2e-06,1e-06,2e-06,0.035,0.033,0.00044,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.024,0.013,-0.0047,0.018,-0.0011,-0.0058,-0.00013,-0.0041,-0.017,-0.14,0.2,-1.8e-06,0.43,0.00045,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.007,0.042,0.043,0.033,1.1e-06,1e-06,2e-06,0.035,0.033,0.00044,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.027,0.015,-0.0059,0.022,-0.0011,-0.0058,-0.00013,-0.0045,-0.017,-0.14,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.0072,0.047,0.048,0.033,1.1e-06,1e-06,2e-06,0.035,0.033,0.00044,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.03,0.013,-0.0049,0.022,-0.0011,-0.0058,-0.00013,-0.0044,-0.018,-0.14,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.0072,0.042,0.042,0.033,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00043,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.03,0.016,-0.0059,0.023,-0.0011,-0.0058,-0.00013,-0.0038,-0.017,-0.14,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.0073,0.047,0.047,0.033,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00043,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.029,0.013,-0.0047,0.023,-0.0011,-0.0058,-0.00012,-0.0033,-0.017,-0.14,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.0073,0.042,0.042,0.033,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.03,0.016,-0.0055,0.022,-0.0011,-0.0058,-0.00012,-0.0022,-0.017,-0.14,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.0074,0.046,0.047,0.033,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.014,0.03,0.014,-0.0046,0.02,-0.0011,-0.0058,-0.00011,-0.0019,-0.017,-0.14,0.2,-2.3e-06,0.43,0.00045,0.00025,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0074,0.041,0.042,0.033,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.03,0.018,-0.0063,0.02,-0.0011,-0.0058,-0.00012,-0.0023,-0.019,-0.14,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.0075,0.046,0.046,0.033,9.9e-07,8.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 +17190000,0.98,-0.009,-0.011,0.18,0.028,-0.021,0.031,0.014,-0.0095,0.023,-0.0011,-0.0058,-0.00012,-0.0033,-0.019,-0.14,0.2,-2.9e-06,0.43,0.00053,0.00033,-0.00033,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0076,0.041,0.042,0.033,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.031,0.017,-0.012,0.023,-0.0011,-0.0058,-0.00013,-0.004,-0.019,-0.14,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.0077,0.045,0.046,0.033,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.00041,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.03,0.016,-0.009,0.023,-0.0011,-0.0058,-0.00012,-0.0027,-0.018,-0.14,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.0076,0.041,0.041,0.033,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.00041,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.03,0.019,-0.012,0.025,-0.0011,-0.0058,-0.00013,-0.003,-0.019,-0.14,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.0078,0.045,0.046,0.033,9.3e-07,8.3e-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 +17590000,0.98,-0.0089,-0.011,0.18,0.021,-0.022,0.029,0.014,-0.0098,0.022,-0.0011,-0.0058,-0.00013,-0.0025,-0.019,-0.14,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.0077,0.04,0.041,0.033,9e-07,8.1e-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 +17690000,0.98,-0.009,-0.011,0.18,0.022,-0.023,0.03,0.016,-0.012,0.025,-0.0011,-0.0058,-0.00013,-0.0023,-0.019,-0.14,0.2,-3.6e-06,0.43,0.00053,0.00031,-0.00033,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0078,0.045,0.045,0.033,9e-07,8e-07,2e-06,0.034,0.031,0.00039,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.031,0.015,-0.011,0.03,-0.0011,-0.0058,-0.00013,-0.0015,-0.019,-0.14,0.2,-3.5e-06,0.43,0.00051,0.00029,-0.00031,0,0,0.095,0.00037,0.00039,0.038,0.016,0.017,0.0078,0.04,0.041,0.033,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00039,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.031,0.017,-0.013,0.034,-0.0011,-0.0058,-0.00012,-0.00093,-0.018,-0.14,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.0079,0.044,0.045,0.033,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00039,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.03,0.016,-0.0083,0.035,-0.0012,-0.0058,-0.00012,-0.00013,-0.02,-0.14,0.2,-3.6e-06,0.43,0.00048,0.00027,-0.00029,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0079,0.04,0.04,0.033,8.5e-07,7.6e-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 +18090000,0.98,-0.009,-0.011,0.18,0.026,-0.021,0.03,0.018,-0.01,0.033,-0.0012,-0.0058,-0.00012,-9.3e-05,-0.02,-0.14,0.2,-3.4e-06,0.43,0.00048,0.00026,-0.00028,0,0,0.095,0.00036,0.00038,0.038,0.017,0.018,0.008,0.044,0.045,0.034,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00038,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.03,0.017,-0.0083,0.031,-0.0012,-0.0058,-0.00011,0.0015,-0.021,-0.13,0.2,-3.6e-06,0.43,0.00045,0.00028,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0079,0.04,0.04,0.034,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00037,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.029,0.02,-0.01,0.03,-0.0012,-0.0058,-0.00011,0.0016,-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.008,0.044,0.044,0.034,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00037,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.029,0.019,-0.0089,0.029,-0.0012,-0.0058,-0.00011,0.0018,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00046,0.0003,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0079,0.039,0.04,0.034,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00036,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.028,0.022,-0.01,0.031,-0.0012,-0.0058,-0.00011,0.0025,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00045,0.00031,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.008,0.043,0.044,0.034,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00036,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.028,0.019,-0.0093,0.033,-0.0012,-0.0058,-0.00011,0.0027,-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.0079,0.039,0.04,0.034,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00035,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.026,0.021,-0.011,0.032,-0.0012,-0.0058,-0.00011,0.0037,-0.02,-0.13,0.2,-4.3e-06,0.43,0.00041,0.00025,-0.00022,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.008,0.043,0.044,0.034,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00035,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.026,0.019,-0.0093,0.03,-0.0012,-0.0058,-0.00011,0.0041,-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.0079,0.039,0.04,0.034,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00034,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.024,0.022,-0.011,0.026,-0.0012,-0.0058,-0.00011,0.0039,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00043,0.00027,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.043,0.034,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00034,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.025,0.019,-0.0097,0.03,-0.0012,-0.0058,-0.00011,0.0046,-0.019,-0.13,0.2,-5.4e-06,0.43,0.00042,0.00026,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.034,7.3e-07,6.5e-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.8 +19090000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.025,0.021,-0.011,0.026,-0.0012,-0.0058,-0.0001,0.0052,-0.019,-0.13,0.2,-5.3e-06,0.43,0.00041,0.00027,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0079,0.042,0.043,0.035,7.3e-07,6.5e-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.8 +19190000,0.98,-0.0086,-0.011,0.18,0.02,-0.018,0.025,0.019,-0.01,0.025,-0.0012,-0.0058,-0.00011,0.005,-0.019,-0.13,0.2,-6.1e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.038,0.039,0.034,7.1e-07,6.3e-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.8 +19290000,0.98,-0.0086,-0.011,0.18,0.021,-0.019,0.025,0.021,-0.012,0.024,-0.0012,-0.0058,-0.00011,0.005,-0.019,-0.13,0.2,-6e-06,0.43,0.00044,0.00029,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0079,0.042,0.043,0.034,7.1e-07,6.3e-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.9 +19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.016,0.026,0.018,-0.0097,0.023,-0.0012,-0.0058,-0.00011,0.0055,-0.019,-0.13,0.2,-6.5e-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.00031,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.026,0.021,-0.012,0.023,-0.0012,-0.0058,-0.00012,0.0049,-0.02,-0.13,0.2,-6.1e-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.00031,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.028,0.019,-0.011,0.023,-0.0012,-0.0058,-0.00012,0.0051,-0.02,-0.13,0.2,-6.3e-06,0.43,0.00043,0.00025,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.015,0.0077,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.0003,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.018,0.026,0.022,-0.013,0.022,-0.0012,-0.0058,-0.00011,0.0056,-0.021,-0.13,0.2,-6e-06,0.43,0.00043,0.00025,-0.00024,0,0,0.095,0.00034,0.00036,0.038,0.014,0.016,0.0078,0.042,0.042,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.0003,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.025,0.021,-0.011,0.019,-0.0012,-0.0058,-0.00012,0.0057,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00043,0.00026,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0077,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00029,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.025,0.023,-0.013,0.017,-0.0012,-0.0058,-0.00012,0.0056,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00043,0.00026,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0077,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19990000,0.98,-0.0089,-0.011,0.18,0.015,-0.016,0.022,0.02,-0.01,0.014,-0.0012,-0.0058,-0.00012,0.0066,-0.02,-0.13,0.2,-7e-06,0.43,0.00042,0.00027,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.038,0.035,6.4e-07,5.7e-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 +20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.019,0.022,0.022,-0.012,0.017,-0.0012,-0.0058,-0.00012,0.0067,-0.021,-0.13,0.2,-7e-06,0.43,0.00043,0.00027,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0076,0.041,0.042,0.035,6.4e-07,5.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.1 +20190000,0.98,-0.0089,-0.012,0.18,0.017,-0.016,0.023,0.022,-0.011,0.017,-0.0012,-0.0058,-0.00012,0.0067,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00043,0.00029,-0.00027,0,0,0.12,0.00034,0.00036,0.038,0.013,0.014,0.0075,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00028,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.023,0.023,-0.012,0.018,-0.0012,-0.0058,-0.00012,0.0067,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00043,0.00029,-0.00028,0,0,0.12,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00027,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.024,0.022,-0.011,0.019,-0.0012,-0.0058,-0.00012,0.0077,-0.022,-0.13,0.2,-7.6e-06,0.43,0.00042,0.00027,-0.00026,0,0,0.12,0.00034,0.00035,0.038,0.013,0.014,0.0075,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00027,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.023,0.023,-0.012,0.017,-0.0012,-0.0058,-0.00012,0.0078,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00041,0.00026,-0.00026,0,0,0.12,0.00034,0.00035,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00026,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.023,0.022,-0.01,0.015,-0.0013,-0.0058,-0.00011,0.009,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00039,0.00024,-0.00025,0,0,0.12,0.00033,0.00035,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00026,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.024,0.022,-0.012,0.016,-0.0013,-0.0058,-0.00012,0.0088,-0.022,-0.13,0.2,-7.6e-06,0.43,0.0004,0.00024,-0.00025,0,0,0.12,0.00033,0.00035,0.038,0.013,0.015,0.0074,0.04,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00026,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.0089,0.019,-0.01,0.015,-0.0013,-0.0058,-0.00011,0.0096,-0.022,-0.13,0.2,-8e-06,0.43,0.00038,0.00024,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00025,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,-3.9e-05,-0.0021,-0.11,0.02,-0.011,0.0084,-0.0013,-0.0058,-0.00011,0.0097,-0.023,-0.13,0.2,-8.8e-06,0.43,0.00038,0.00037,-0.00019,0,0,0.11,0.00033,0.00035,0.038,0.013,0.015,0.0073,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00025,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.0066,-0.0013,-0.0058,-0.00011,0.0099,-0.023,-0.13,0.2,-8.8e-06,0.43,0.00038,0.00035,-0.00015,0,0,0.093,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00024,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.037,-0.0013,-0.0058,-0.00011,0.0099,-0.023,-0.13,0.2,-7e-06,0.43,0.00043,0.00016,-0.00019,0,0,0.063,0.00033,0.00035,0.038,0.014,0.015,0.0072,0.04,0.041,0.035,5.6e-07,4.9e-07,1.7e-06,0.031,0.028,0.00024,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21190000,0.98,-6.4e-05,-0.0063,0.18,-0.029,0.039,-0.49,0.013,-0.0039,-0.074,-0.0013,-0.0058,-0.0001,0.0097,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00044,0.00018,-0.00018,0,0,0.026,0.00033,0.00034,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00024,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.62,0.0099,-0.00035,-0.13,-0.0013,-0.0058,-0.00011,0.0092,-0.024,-0.13,0.2,-7e-06,0.43,0.00043,0.00022,-0.00011,0,0,-0.032,0.00033,0.00034,0.037,0.014,0.015,0.0071,0.04,0.041,0.035,5.4e-07,4.8e-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 +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.0093,-0.024,-0.13,0.2,-6.5e-06,0.43,0.00045,0.00015,-0.00012,0,0,-0.097,0.00032,0.00034,0.037,0.013,0.014,0.007,0.037,0.038,0.035,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00023,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.28,-0.0013,-0.0058,-0.0001,0.0097,-0.024,-0.13,0.2,-6.5e-06,0.43,0.00044,0.00017,-0.00017,0,0,-0.18,0.00032,0.00034,0.037,0.014,0.016,0.007,0.04,0.041,0.035,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00023,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.031,-1,0.0044,0.0098,-0.37,-0.0013,-0.0058,-9.4e-05,0.01,-0.023,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00022,-0.00018,0,0,-0.27,0.00032,0.00034,0.037,0.013,0.015,0.0069,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00022,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.7e-05,0.011,-0.024,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00026,-0.00017,0,0,-0.39,0.00032,0.00034,0.037,0.014,0.016,0.0069,0.04,0.041,0.035,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00022,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.007,0.012,-0.61,-0.0013,-0.0058,-7.8e-05,0.011,-0.023,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00026,-0.00022,0,0,-0.51,0.00032,0.00033,0.037,0.013,0.015,0.0069,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.00022,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,-8e-05,0.011,-0.023,-0.13,0.2,-6.9e-06,0.43,0.00037,0.00028,-0.00021,0,0,-0.65,0.00032,0.00033,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.027,0.00021,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.00084,0.013,-1.4,0.01,0.011,-0.88,-0.0013,-0.0058,-7.4e-05,0.011,-0.022,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00029,-0.00023,0,0,-0.78,0.00031,0.00033,0.037,0.013,0.015,0.0068,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22090000,0.98,-0.0071,-0.0098,0.18,0.0012,0.0094,-1.4,0.0095,0.012,-1,-0.0013,-0.0058,-6.6e-05,0.012,-0.022,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00031,-0.00024,0,0,-0.93,0.00031,0.00033,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00021,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.005,-1.4,0.015,0.0079,-1.2,-0.0013,-0.0058,-5.7e-05,0.013,-0.02,-0.13,0.2,-6.7e-06,0.43,0.0004,0.00032,-0.00024,0,0,-1.1,0.00031,0.00032,0.037,0.013,0.014,0.0067,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00021,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.00065,-1.4,0.016,0.008,-1.3,-0.0013,-0.0058,-5.9e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00039,0.00032,-0.00024,0,0,-1.2,0.00031,0.00032,0.037,0.014,0.015,0.0067,0.04,0.041,0.034,4.8e-07,4.2e-07,1.6e-06,0.029,0.027,0.0002,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.0092,-1.4,0.022,-0.00079,-1.5,-0.0013,-0.0058,-6.2e-05,0.011,-0.02,-0.13,0.2,-6.7e-06,0.43,0.00041,0.00032,-0.00026,0,0,-1.4,0.0003,0.00032,0.037,0.013,0.014,0.0066,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.0002,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.6e-05,0.011,-0.02,-0.13,0.2,-7e-06,0.43,0.00042,0.00034,-0.00028,0,0,-1.5,0.00031,0.00032,0.037,0.013,0.015,0.0066,0.04,0.041,0.034,4.7e-07,4.1e-07,1.6e-06,0.029,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22590000,0.98,-0.0086,-0.011,0.18,0.029,-0.024,-1.4,0.034,-0.01,-1.7,-0.0013,-0.0058,-5.8e-05,0.011,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00042,0.00036,-0.00027,0,0,-1.6,0.0003,0.00032,0.037,0.012,0.014,0.0065,0.036,0.038,0.034,4.5e-07,4.1e-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 +22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.029,-1.4,0.038,-0.013,-1.9,-0.0013,-0.0058,-6e-05,0.011,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00036,-0.00029,0,0,-1.8,0.0003,0.00032,0.037,0.013,0.015,0.0065,0.04,0.041,0.034,4.5e-07,4.1e-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 +22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.036,-1.4,0.048,-0.023,-2,-0.0013,-0.0058,-6.3e-05,0.011,-0.02,-0.13,0.2,-6.7e-06,0.43,0.00041,0.00033,-0.00031,0,0,-1.9,0.0003,0.00031,0.037,0.012,0.014,0.0065,0.036,0.038,0.034,4.4e-07,4e-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 +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.5e-05,0.011,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00041,0.00034,-0.00029,0,0,-2.1,0.0003,0.00031,0.037,0.013,0.015,0.0065,0.04,0.041,0.034,4.4e-07,4e-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 +22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.046,-1.4,0.061,-0.035,-2.3,-0.0013,-0.0058,-4.6e-05,0.011,-0.02,-0.13,0.2,-6.8e-06,0.43,0.00041,0.00031,-0.00027,0,0,-2.2,0.0003,0.00031,0.037,0.012,0.014,0.0064,0.036,0.038,0.034,4.3e-07,3.9e-07,1.6e-06,0.028,0.027,0.00019,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.5e-05,0.011,-0.02,-0.13,0.2,-6.8e-06,0.43,0.00039,0.00032,-0.00025,0,0,-2.4,0.0003,0.00031,0.037,0.013,0.014,0.0064,0.04,0.041,0.034,4.3e-07,3.9e-07,1.5e-06,0.028,0.027,0.00018,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.8e-05,0.011,-0.019,-0.13,0.2,-7.6e-06,0.43,0.00038,0.00029,-0.00025,0,0,-2.5,0.00029,0.00031,0.037,0.012,0.013,0.0063,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00018,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.5e-05,0.011,-0.02,-0.13,0.2,-7.6e-06,0.43,0.00034,0.00033,-0.00025,0,0,-2.7,0.00029,0.00031,0.037,0.013,0.014,0.0063,0.039,0.041,0.034,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00018,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.8e-05,0.012,-0.019,-0.13,0.2,-7.9e-06,0.43,0.00035,0.0003,-0.00024,0,0,-2.8,0.00029,0.0003,0.037,0.012,0.013,0.0063,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00018,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.6e-06,0.43,0.00034,0.00036,-0.00028,0,0,-2.9,0.00029,0.0003,0.037,0.013,0.014,0.0063,0.039,0.041,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 +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.7e-05,0.012,-0.019,-0.13,0.2,-8.6e-06,0.43,0.00029,0.00032,-0.00024,0,0,-3.1,0.00029,0.0003,0.037,0.012,0.013,0.0062,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 +23690000,0.98,-0.01,-0.014,0.18,0.074,-0.066,-1.3,0.11,-0.082,-3.3,-0.0013,-0.0058,-3.9e-05,0.013,-0.019,-0.13,0.2,-8.4e-06,0.43,0.00028,0.00035,-0.00024,0,0,-3.2,0.00029,0.0003,0.037,0.012,0.014,0.0062,0.039,0.041,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 +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.7e-05,0.014,-0.019,-0.13,0.2,-8.1e-06,0.43,0.00026,0.00038,-0.00022,0,0,-3.3,0.00029,0.0003,0.037,0.011,0.013,0.0061,0.036,0.037,0.033,4e-07,3.6e-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 +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.5e-05,0.014,-0.02,-0.13,0.2,-8.1e-06,0.43,0.00025,0.0004,-0.00025,0,0,-3.4,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.039,0.041,0.033,4e-07,3.6e-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 +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.1e-05,0.015,-0.019,-0.13,0.2,-8.2e-06,0.43,0.00021,0.00042,1.6e-06,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.0061,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.4e-05,0.015,-0.019,-0.13,0.2,-8.2e-06,0.43,0.00023,0.00039,1.7e-06,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.0061,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00016,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.075,0.089,0.15,-0.11,-3.6,-0.0013,-0.0058,-4.4e-05,0.016,-0.019,-0.13,0.2,-7.8e-06,0.43,0.00022,0.00036,0.0001,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.006,0.036,0.037,0.033,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00016,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.2e-05,0.016,-0.019,-0.13,0.2,-7.4e-06,0.43,0.00026,0.00031,9.6e-05,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.006,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00016,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.1e-05,0.018,-0.02,-0.13,0.2,-6.1e-06,0.43,0.00025,0.00035,0.00016,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.006,0.035,0.037,0.033,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00016,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.7e-05,0.018,-0.02,-0.13,0.2,-6.1e-06,0.43,0.00017,0.00046,0.00021,0,0,-3.5,0.00028,0.00029,0.037,0.012,0.013,0.006,0.038,0.04,0.033,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00016,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.8e-05,0.02,-0.021,-0.13,0.2,-4.8e-06,0.43,0.00021,0.00043,0.00022,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.0059,0.035,0.037,0.033,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.7e-05,0.02,-0.021,-0.13,0.2,-5e-06,0.43,0.0002,0.00046,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0059,0.038,0.04,0.033,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.5e-05,0.021,-0.022,-0.13,0.2,-4.4e-06,0.43,0.00019,0.00046,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0059,0.035,0.036,0.032,3.6e-07,3.3e-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 +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,-3.9e-05,0.021,-0.022,-0.13,0.2,-4.2e-06,0.43,0.00019,0.00047,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0059,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00015,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.3e-05,0.023,-0.023,-0.13,0.2,-4.4e-06,0.43,0.00016,0.00058,0.00025,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.025,0.00015,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.023,-0.023,-0.13,0.2,-5.1e-06,0.43,0.00014,0.00065,0.00028,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.3e-06,0.027,0.025,0.00015,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.1e-05,0.025,-0.023,-0.13,0.2,-5e-06,0.43,0.00012,0.00068,0.00027,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00015,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.042,0.2,-0.12,-3.5,-0.0014,-0.0058,-7.8e-05,0.024,-0.023,-0.13,0.2,-5.6e-06,0.43,0.00011,0.00071,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.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00015,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.026,-0.024,-0.13,0.2,-6.4e-06,0.43,7.3e-05,0.00076,0.00026,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,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.04,0.19,-0.12,-3.5,-0.0014,-0.0058,-9.6e-05,0.026,-0.025,-0.13,0.2,-6.2e-06,0.43,6.7e-05,0.00072,0.00023,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,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.027,-0.025,-0.13,0.2,-7e-06,0.43,3.6e-05,0.00075,0.0002,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,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.048,0.031,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.027,-0.025,-0.13,0.2,-7.1e-06,0.43,4.2e-05,0.00077,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.039,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 +25790000,0.98,-0.012,-0.011,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.6e-06,0.43,-1.8e-05,0.0007,0.0002,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,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 +25890000,0.98,-0.012,-0.012,0.18,0.0061,-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.7e-06,0.43,-3.8e-05,0.00068,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.039,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 +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.03,-0.026,-0.13,0.2,-9.1e-06,0.43,-9.3e-05,0.00066,0.00014,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.026,0.025,0.00014,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.025,0.17,-0.1,-3.5,-0.0014,-0.0058,-0.00014,0.03,-0.026,-0.13,0.2,-8.6e-06,0.43,-9e-05,0.00064,0.00017,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0057,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.026,0.025,0.00014,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,-9e-06,0.43,-0.00011,0.00064,0.00019,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,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.025,0.015,0.16,-0.095,-3.5,-0.0015,-0.0058,-0.00015,0.031,-0.027,-0.13,0.2,-9.6e-06,0.43,-0.00012,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.00016,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,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.012,0.18,-0.023,-0.015,0.028,0.14,-0.087,-3.5,-0.0015,-0.0058,-0.00016,0.032,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00016,0.00066,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,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.028,0.13,-0.079,-3.5,-0.0015,-0.0058,-0.00017,0.033,-0.027,-0.13,0.2,-1.2e-05,0.43,-0.00019,0.00069,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,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.026,-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.00069,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,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 +26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.0018,0.026,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.00023,0.00067,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.00013,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.0047,0.022,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.00018,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00023,0.00066,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,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 +26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.012,0.021,0.099,-0.065,-3.5,-0.0015,-0.0058,-0.00019,0.034,-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.011,0.012,0.0055,0.035,0.036,0.031,3.1e-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 +27090000,0.98,-0.0085,-0.013,0.18,-0.05,0.018,0.024,0.094,-0.064,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00063,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.00013,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.027,-0.13,0.2,-1.4e-05,0.43,-0.00026,0.00062,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.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00013,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.027,-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.0055,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.064,-0.045,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.00033,0.00055,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,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.0003,0.00052,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0055,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.00028,0.00046,0.00021,0,0,-3.3,0.00028,0.00029,0.037,0.011,0.012,0.0055,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.00027,0.00045,0.00019,0,0,-3.2,0.00028,0.00029,0.037,0.011,0.012,0.0055,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.034,-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.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.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00041,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.00035,0.00022,0,0,-3,0.00028,0.00029,0.037,0.011,0.012,0.0054,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.012,-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.0014,-0.0058,-0.00019,0.033,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00025,0.00036,0.00022,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0054,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 +28290000,0.98,-0.0081,-0.013,0.18,-0.081,0.051,0.81,-0.0031,-0.0068,-2.9,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00038,0.00019,0,0,-2.8,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 +28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.054,0.81,-0.0096,-0.0024,-2.8,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00031,0.00029,0.0002,0,0,-2.7,0.00028,0.00029,0.036,0.011,0.012,0.0054,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 +28490000,0.98,-0.0084,-0.014,0.18,-0.085,0.058,0.81,-0.019,0.0031,-2.7,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00028,0.00028,0.00023,0,0,-2.6,0.00029,0.00029,0.036,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 +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.7e-05,0.43,-0.00025,0.00026,0.00022,0,0,-2.5,0.00028,0.00029,0.036,0.011,0.012,0.0054,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00012,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.0079,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00022,0.00026,0.00022,0,0,-2.5,0.00029,0.00029,0.036,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00012,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.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.00016,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.028,-0.12,0.2,-1.8e-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.00028,5e-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.0003,3.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.8,-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,-9.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.00012,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.00025,0.00025,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,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.068,0.038,-2,-0.0014,-0.0058,-0.0001,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00038,-0.00022,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.6e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00043,-0.00032,0.00022,0,0,-1.8,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,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,-7.9e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00045,-0.00029,0.0002,0,0,-1.7,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,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.042,-1.7,-0.0014,-0.0058,-6.3e-05,0.027,-0.028,-0.12,0.2,-2.5e-05,0.43,-0.0005,-0.00041,0.00021,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0053,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.6e-05,0.027,-0.028,-0.12,0.2,-2.5e-05,0.43,-0.00052,-0.00038,0.00019,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0053,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.5e-05,0.026,-0.028,-0.12,0.2,-2.6e-05,0.43,-0.00051,-0.00043,0.0002,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.00049,0.00025,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.8e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00047,-0.00071,0.00031,0,0,-1.4,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.3e-07,0.025,0.024,0.00011,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.6e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00051,-0.00076,0.00031,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.00011,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,-3.9e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00064,-0.00097,0.00031,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.00011,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.3e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00069,-0.00096,0.00029,0,0,-1.1,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.2e-07,0.025,0.023,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30590000,0.98,-0.0074,-0.013,0.18,-0.064,0.041,0.8,-0.077,0.051,-1.2,-0.0014,-0.0058,-1.7e-05,0.024,-0.03,-0.12,0.2,-3e-05,0.43,-0.00079,-0.0011,0.00029,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.00011,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.7e-05,0.024,-0.03,-0.12,0.2,-3.1e-05,0.43,-0.00077,-0.001,0.00029,0,0,-1,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.00011,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.3e-05,0.024,-0.03,-0.12,0.2,-3.2e-05,0.43,-0.00084,-0.0012,0.00032,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,-2e-05,0.024,-0.031,-0.12,0.2,-3.3e-05,0.43,-0.00075,-0.0011,0.00034,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.79,-0.071,0.049,-0.88,-0.0014,-0.0057,-1.3e-05,0.023,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00078,-0.0013,0.00037,0,0,-0.78,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.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.7e-05,0.023,-0.032,-0.12,0.2,-3.4e-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.1e-06,0.023,-0.033,-0.12,0.2,-3.4e-05,0.43,-0.00083,-0.0013,0.00038,0,0,-0.64,0.00028,0.00028,0.035,0.011,0.012,0.0052,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,4e-06,0.023,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00087,-0.0012,0.00036,0,0,-0.57,0.00028,0.00028,0.035,0.011,0.012,0.0052,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,3.3e-06,0.023,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00095,-0.0015,0.00041,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,1.7e-06,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.001,-0.0017,0.00042,0,0,-0.42,0.00028,0.00028,0.035,0.011,0.012,0.0052,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.00044,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,0.0001,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,2e-05,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.0012,-0.0018,0.00042,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,0.0001,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.5e-05,0.023,-0.034,-0.12,0.2,-3.1e-05,0.43,-0.0013,-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,0.0001,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.00078,0.8,-0.049,0.039,-0.23,-0.0013,-0.0057,2.9e-05,0.023,-0.033,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0021,0.00046,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,0.0001,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.00031,0.79,-0.036,0.036,-0.17,-0.0013,-0.0057,2.6e-05,0.023,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0022,0.00052,0,0,-0.068,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,0.0001,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.096,-0.0013,-0.0057,2.6e-05,0.023,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0023,0.00053,0,0,0.0043,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,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32190000,0.99,-0.0079,-0.014,0.17,-0.013,-0.0073,0.8,-0.026,0.034,-0.027,-0.0013,-0.0057,2.2e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0024,0.00057,0,0,0.073,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,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32290000,0.99,-0.0078,-0.014,0.17,-0.013,-0.0099,0.8,-0.027,0.033,0.042,-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.00058,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.9e-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.015,0.03,0.12,-0.0013,-0.0057,2.3e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0016,-0.0027,0.00064,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.9e-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.077,-0.014,0.024,0.12,-0.0013,-0.0057,2e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0015,-0.0027,0.00063,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.9e-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.08,0.0014,0.02,0.1,-0.0013,-0.0057,1.9e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.0007,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.9e-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.081,0.0033,0.012,0.088,-0.0013,-0.0057,1.8e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.0007,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.9e-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.082,0.015,0.0092,0.073,-0.0013,-0.0057,1.6e-05,0.024,-0.034,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0022,0.00077,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.9e-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.084,0.017,0.00073,0.058,-0.0013,-0.0057,2e-05,0.024,-0.034,-0.12,0.2,-2.6e-05,0.43,-0.0015,-0.0021,0.00078,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.9e-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.083,0.028,-0.0031,0.044,-0.0014,-0.0057,2.2e-05,0.024,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00084,0,0,0.14,0.00027,0.00027,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.9e-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.08,0.029,-0.012,0.037,-0.0014,-0.0057,2.2e-05,0.024,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00084,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.9e-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.079,0.037,-0.016,0.029,-0.0014,-0.0057,1.3e-05,0.025,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0015,-0.002,0.00087,0,0,0.13,0.00027,0.00027,0.034,0.011,0.012,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.9e-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.079,0.037,-0.024,0.021,-0.0014,-0.0057,2.4e-05,0.025,-0.033,-0.12,0.2,-2.1e-05,0.43,-0.0016,-0.0021,0.0009,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.9e-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.077,0.043,-0.022,0.012,-0.0014,-0.0057,1.6e-05,0.027,-0.032,-0.12,0.2,-1.8e-05,0.43,-0.0016,-0.002,0.00095,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.8e-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.00022,-0.093,-0.076,0.042,-0.031,0.0027,-0.0014,-0.0057,2.1e-05,0.027,-0.032,-0.12,0.2,-1.7e-05,0.43,-0.0017,-0.0022,0.00097,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.8e-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.073,0.046,-0.029,-0.0052,-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.8e-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.074,0.046,-0.038,-0.013,-0.0014,-0.0057,2.5e-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.7e-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.052,-0.036,-0.02,-0.0014,-0.0057,1.5e-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.0051,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.7e-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.068,0.051,-0.045,-0.027,-0.0014,-0.0057,2.5e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0018,-0.0019,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.7e-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.055,-0.04,-0.031,-0.0014,-0.0057,1.2e-05,0.033,-0.031,-0.12,0.2,-8.8e-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.6e-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.063,0.054,-0.049,-0.035,-0.0014,-0.0057,1.5e-05,0.032,-0.031,-0.12,0.2,-9.3e-06,0.43,-0.0017,-0.0017,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.6e-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.038,-0.0014,-0.0057,1.1e-05,0.034,-0.03,-0.12,0.2,-6.9e-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.6e-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.059,0.056,-0.052,-0.044,-0.0014,-0.0057,1.7e-05,0.034,-0.03,-0.12,0.2,-6.2e-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.6e-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.086,-0.054,0.058,-0.047,-0.048,-0.0014,-0.0056,1e-05,0.036,-0.03,-0.12,0.2,-4.1e-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.5e-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.051,-0.0014,-0.0056,1.9e-05,0.036,-0.03,-0.12,0.2,-3.7e-06,0.43,-0.0017,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.5e-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.023,-0.0014,-0.0056,1.1e-05,0.037,-0.03,-0.12,0.2,-1.2e-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.5e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 +34690000,0.98,-0.0093,-0.013,0.17,-0.03,-0.079,1.7,0.056,-0.058,0.097,-0.0014,-0.0056,1.5e-05,0.037,-0.03,-0.12,0.2,-9.4e-07,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.4e-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.071,2.7,0.058,-0.052,0.28,-0.0015,-0.0056,8.3e-06,0.039,-0.03,-0.12,0.2,1.7e-06,0.43,-0.0017,-0.0014,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.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 +34890000,0.98,-0.0092,-0.012,0.17,-0.038,-0.069,3.7,0.055,-0.058,0.57,-0.0015,-0.0056,1.2e-05,0.04,-0.03,-0.12,0.2,1.8e-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.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 From 6c24413888a27bc46c570f09210a13caa59f96aa Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Jul 2024 14:19:33 -0400 Subject: [PATCH 07/31] ekf2: filter flow vel (used for flow velocity reset) - individual flow samples can be quite erratic --- msg/VehicleOpticalFlowVel.msg | 3 +++ .../optical_flow/optical_flow_control.cpp | 15 +++++++++++++-- src/modules/ekf2/EKF/ekf.h | 11 ++++++++--- src/modules/ekf2/EKF2.cpp | 3 +++ src/modules/ekf2/test/test_EKF_flow.cpp | 6 ++---- 5 files changed, 29 insertions(+), 9 deletions(-) diff --git a/msg/VehicleOpticalFlowVel.msg b/msg/VehicleOpticalFlowVel.msg index 947131da4dd1..9d9b0ad87625 100644 --- a/msg/VehicleOpticalFlowVel.msg +++ b/msg/VehicleOpticalFlowVel.msg @@ -4,6 +4,9 @@ uint64 timestamp_sample # the timestamp of the raw data (microsec float32[2] vel_body # velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) float32[2] vel_ne # same as vel_body but in local frame (m/s) +float32[2] vel_body_filtered # filtered velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) +float32[2] vel_ne_filtered # filtered same as vel_body_filtered but in local frame (m/s) + float32[2] flow_rate_uncompensated # integrated optical flow measurement (rad/s) float32[2] flow_rate_compensated # integrated optical flow measurement compensated for angular motion (rad/s) 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 95db812faeb5..becece91c188 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 @@ -122,8 +122,16 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) const float range = predictFlowRange(); _flow_vel_body(0) = -flow_compensated(1) * range; _flow_vel_body(1) = flow_compensated(0) * range; - _flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f)); + if (_flow_counter == 0) { + _flow_vel_body_lpf.reset(_flow_vel_body); + _flow_counter = 1; + + } else { + + _flow_vel_body_lpf.update(_flow_vel_body); + _flow_counter++; + } // Check if we are in-air and require optical flow to control position drift bool is_flow_required = _control_status.flags.in_air @@ -144,6 +152,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && is_quality_good && is_magnitude_good && is_tilt_good + && (_flow_counter > 10) && (isTerrainEstimateValid() || isHorizontalAidingActive()) && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching @@ -219,7 +228,7 @@ void Ekf::resetFlowFusion() _information_events.flags.reset_vel_to_flow = true; const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(_flow_sample_delayed); - resetHorizontalVelocityTo(_flow_vel_ne, flow_vel_var); + 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) { @@ -273,6 +282,8 @@ void Ekf::stopFlowFusion() _innov_check_fail_status.flags.reject_optflow_X = false; _innov_check_fail_status.flags.reject_optflow_Y = false; + + _flow_counter = 0; } } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 7be3fdf92afb..4449b2d23318 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -122,7 +122,10 @@ class Ekf final : public EstimatorInterface const auto &aid_src_optical_flow() const { return _aid_src_optical_flow; } const Vector2f &getFlowVelBody() const { return _flow_vel_body; } - const Vector2f &getFlowVelNE() const { return _flow_vel_ne; } + Vector2f getFlowVelNE() const { return Vector2f(_R_to_earth * Vector3f(getFlowVelBody()(0), getFlowVelBody()(1), 0.f)); } + + const Vector2f &getFilteredFlowVelBody() const { return _flow_vel_body_lpf.getState(); } + Vector2f getFilteredFlowVelNE() const { return Vector2f(_R_to_earth * Vector3f(getFilteredFlowVelBody()(0), getFilteredFlowVelBody()(1), 0.f)); } const Vector2f &getFlowCompensated() const { return _flow_rate_compensated; } const Vector2f &getFlowUncompensated() const { return _flow_sample_delayed.flow_rate; } @@ -634,10 +637,12 @@ class Ekf final : public EstimatorInterface // optical flow processing Vector3f _flow_gyro_bias{}; ///< bias errors in optical flow sensor rate gyro outputs (rad/sec) - Vector2f _flow_vel_body{}; ///< velocity from corrected flow measurement (body frame)(m/s) - Vector2f _flow_vel_ne{}; ///< velocity from corrected flow measurement (local frame) (m/s) Vector3f _ref_body_rate{}; + Vector2f _flow_vel_body{}; ///< velocity from corrected flow measurement (body frame)(m/s) + AlphaFilter _flow_vel_body_lpf{0.1f}; ///< filtered velocity from corrected flow measurement (body frame)(m/s) + uint32_t _flow_counter{0}; ///< number of flow samples read for initialization + Vector2f _flow_rate_compensated{}; ///< measured angular rate of the image about the X and Y body axes after removal of body rotation (rad/s), RH rotation is positive #endif // CONFIG_EKF2_OPTICAL_FLOW diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index bb986208de84..c339548b8cef 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2027,6 +2027,9 @@ void EKF2::PublishOpticalFlowVel(const hrt_abstime ×tamp) _ekf.getFlowVelBody().copyTo(flow_vel.vel_body); _ekf.getFlowVelNE().copyTo(flow_vel.vel_ne); + _ekf.getFilteredFlowVelBody().copyTo(flow_vel.vel_body_filtered); + _ekf.getFilteredFlowVelNE().copyTo(flow_vel.vel_ne_filtered); + _ekf.getFlowUncompensated().copyTo(flow_vel.flow_rate_uncompensated); _ekf.getFlowCompensated().copyTo(flow_vel.flow_rate_compensated); diff --git a/src/modules/ekf2/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp index 787560ce1bf6..650d168a98b7 100644 --- a/src/modules/ekf2/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -203,10 +203,8 @@ TEST_F(EkfFlowTest, inAirConvergence) _sensor_simulator.setTrajectoryTargetVelocity(simulated_velocity); _ekf_wrapper.enableFlowFusion(); _sensor_simulator.startFlow(); - // Let it reset but not fuse more measurements. We actually need to send 2 - // samples to get a reset because the first one cannot be used as the gyro - // compensation needs to be accumulated between two samples. - _sensor_simulator.runTrajectorySeconds(0.14); + + _sensor_simulator.runTrajectorySeconds(1.0); // THEN: estimated velocity should match simulated velocity Vector3f estimated_velocity = _ekf->getVelocity(); From f3d58cdf10a31998835fab6076b67cd52644ae5c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 26 Aug 2024 14:11:30 -0400 Subject: [PATCH 08/31] ekf2: resetFlowFusion() pass flowSample by const ref --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 8 ++++---- src/modules/ekf2/EKF/ekf.h | 2 +- 2 files changed, 5 insertions(+), 5 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 becece91c188..dbbc1a72961b 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 @@ -169,7 +169,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) // handle the case when we have optical flow, are reliant on it, but have not been using it for an extended period if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)) { if (is_flow_required && is_quality_good && is_magnitude_good) { - resetFlowFusion(); + resetFlowFusion(flow_sample); if (_control_status.flags.opt_flow_terrain && !isTerrainEstimateValid()) { resetTerrainToFlow(); @@ -203,7 +203,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) } else { if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) { ECL_INFO("starting optical flow, resetting"); - resetFlowFusion(); + resetFlowFusion(flow_sample); _control_status.flags.opt_flow = true; } else if (_control_status.flags.opt_flow_terrain) { @@ -222,12 +222,12 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) } } -void Ekf::resetFlowFusion() +void Ekf::resetFlowFusion(const flowSample &flow_sample) { ECL_INFO("reset velocity to flow"); _information_events.flags.reset_vel_to_flow = true; - const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(_flow_sample_delayed); + 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 diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 4449b2d23318..e9715f3e372c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -878,7 +878,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_OPTICAL_FLOW) // control fusion of optical flow observations void controlOpticalFlowFusion(const imuSample &imu_delayed); - void resetFlowFusion(); + void resetFlowFusion(const flowSample &flow_sample); void stopFlowFusion(); void updateOnGroundMotionForOpticalFlowChecks(); From 9169a7c5fc34bae38d1a86d6eae8fe38162ef83f Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 20 Aug 2024 14:34:25 +0200 Subject: [PATCH 09/31] ekf2: split horizontal and vertical origin reset Allow partial resets (only lat/lon or only altitude) --- src/modules/ekf2/EKF/ekf.h | 5 ++ src/modules/ekf2/EKF/ekf_helper.cpp | 114 ++++++++++++++++++---------- 2 files changed, 78 insertions(+), 41 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index e9715f3e372c..44f635573c04 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -261,6 +261,8 @@ class Ekf final : public EstimatorInterface // get the ekf WGS-84 origin position and height and the system time it was last set // return true if the origin is valid bool getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const; + bool checkLatLonValidity(double latitude, double longitude, float eph = 0.f); + bool checkAltitudeValidity(float altitude, float epv = 0.f); bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = 0.f, float epv = 0.f); // get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position @@ -765,6 +767,9 @@ 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); + // 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); void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 01821fd97bb8..4ba346e1f9a0 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -72,63 +72,95 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo return _NED_origin_initialised; } +bool Ekf::checkLatLonValidity(const double latitude, const double longitude, const float eph) +{ + const bool lat_valid = (PX4_ISFINITE(latitude) && (abs(latitude) <= 90)); + const bool lon_valid = (PX4_ISFINITE(longitude) && (abs(longitude) <= 180)); + const bool eph_valid = (PX4_ISFINITE(eph) && (eph >= 0.f)); + + return (lat_valid && lon_valid && eph_valid); +} + +bool Ekf::checkAltitudeValidity(const float altitude, const float epv) +{ + // sanity check valid altitude anywhere between the Mariana Trench and edge of Space + const bool alt_valid = (PX4_ISFINITE(altitude) && ((altitude > -12'000.f) && (altitude < 100'000.f))); + const bool epv_valid = (PX4_ISFINITE(epv) && (epv >= 0.f)); + + return alt_valid && epv_valid; +} + bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph, const float epv) { - // sanity check valid latitude/longitude and altitude anywhere between the Mariana Trench and edge of Space - if (PX4_ISFINITE(latitude) && (abs(latitude) <= 90) - && PX4_ISFINITE(longitude) && (abs(longitude) <= 180) - && PX4_ISFINITE(altitude) && (altitude > -12'000.f) && (altitude < 100'000.f) - ) { - bool current_pos_available = false; - double current_lat = static_cast(NAN); - double current_lon = static_cast(NAN); - - // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { - _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); - current_pos_available = true; - } + if (!setLatLonOrigin(latitude, longitude, eph)) { + return false; + } + + // altitude is optional + setAltOrigin(altitude, epv); + + return true; +} - const float gps_alt_ref_prev = _gps_alt_ref; +bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const float eph) +{ + if (!checkLatLonValidity(latitude, longitude, eph)) { + return false; + } - // reinitialize map projection to latitude, longitude, altitude, and reset position - _pos_ref.initReference(latitude, longitude, _time_delayed_us); - _gps_alt_ref = altitude; + bool current_pos_available = false; + double current_lat = static_cast(NAN); + double current_lon = static_cast(NAN); - _gpos_origin_eph = eph; - _gpos_origin_epv = epv; + // if we are already doing aiding, correct for the change in position since the EKF started navigating + if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { + _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); + current_pos_available = true; + } - _NED_origin_initialised = true; + // reinitialize map projection to latitude, longitude, altitude, and reset position + _pos_ref.initReference(latitude, longitude, _time_delayed_us); + _gpos_origin_eph = eph; - _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(latitude))); + _NED_origin_initialised = true; - 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); - } + 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); + } + + return true; +} - if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { - // determine current z - const float z_prev = _state.pos(2); - const float current_alt = -z_prev + gps_alt_ref_prev; +bool Ekf::setAltOrigin(const float altitude, const float epv) +{ + if (!checkAltitudeValidity(altitude, epv)) { + return false; + } + + const float gps_alt_ref_prev = _gps_alt_ref; + _gps_alt_ref = altitude; + _gpos_origin_epv = epv; + + if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { + // 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(); + 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)); + 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); + // adjust existing GPS height bias + _gps_hgt_b_est.setBias(gps_hgt_bias); #endif // CONFIG_EKF2_GNSS - } - - return true; } - return false; + return true; } void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const From af752536b92e3dc88a30a3c90e0d17d05d209b66 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 21 Aug 2024 16:21:17 +0200 Subject: [PATCH 10/31] ekf2: extract setting origin from current lat/lon/alt This is not only needed when GNSS is available but also for other global sources of position (e.g.: aux global pos and manual pos updates) --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 23 +----- src/modules/ekf2/EKF/ekf.h | 11 ++- src/modules/ekf2/EKF/ekf_helper.cpp | 79 ++++++++++++++++--- 3 files changed, 77 insertions(+), 36 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 4467ff9f7e28..e3c40dda7774 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -59,34 +59,15 @@ void Ekf::collect_gps(const gnssSample &gps) { if (_filter_initialised && !_NED_origin_initialised && _gps_checks_passed) { // If we have good GPS data set the origin's WGS-84 position to the last gps fix - const double lat = gps.lat; - const double lon = gps.lon; - if (!_pos_ref.isInitialized()) { - _pos_ref.initReference(lat, lon, gps.time_us); - - // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (isHorizontalAidingActive()) { - 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, gps.time_us); - } + 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)) { - _gps_alt_ref = gps.alt + _state.pos(2); + setAltOriginFromCurrentPos(gps.alt, gps.vacc); } - _NED_origin_initialised = true; - - // save the horizontal and vertical position uncertainty of the origin - _gpos_origin_eph = gps.hacc; - _gpos_origin_epv = gps.vacc; - - _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(gps.lat))); - _information_events.flags.gps_checks_passed = true; ECL_INFO("GPS origin set to lat=%.6f, lon=%.6f", diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 44f635573c04..5f2ba8c95fb4 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -261,9 +261,11 @@ class Ekf final : public EstimatorInterface // get the ekf WGS-84 origin position and height and the system time it was last set // return true if the origin is valid bool getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const; - bool checkLatLonValidity(double latitude, double longitude, float eph = 0.f); - bool checkAltitudeValidity(float altitude, float epv = 0.f); - bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = 0.f, float epv = 0.f); + 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); // 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; @@ -770,6 +772,9 @@ class Ekf final : public EstimatorInterface bool setLatLonOrigin(double latitude, double longitude, float eph = NAN); bool setAltOrigin(float altitude, float epv = NAN); + bool setLatLonOriginFromCurrentPos(double latitude, double longitude, float eph = NAN); + bool setAltOriginFromCurrentPos(float altitude, float epv = 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); void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 4ba346e1f9a0..6e3bdf3bab45 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -72,22 +72,18 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo return _NED_origin_initialised; } -bool Ekf::checkLatLonValidity(const double latitude, const double longitude, const float eph) +bool Ekf::checkLatLonValidity(const double latitude, const double longitude) { const bool lat_valid = (PX4_ISFINITE(latitude) && (abs(latitude) <= 90)); const bool lon_valid = (PX4_ISFINITE(longitude) && (abs(longitude) <= 180)); - const bool eph_valid = (PX4_ISFINITE(eph) && (eph >= 0.f)); - return (lat_valid && lon_valid && eph_valid); + return (lat_valid && lon_valid); } -bool Ekf::checkAltitudeValidity(const float altitude, const float epv) +bool Ekf::checkAltitudeValidity(const float altitude) { // sanity check valid altitude anywhere between the Mariana Trench and edge of Space - const bool alt_valid = (PX4_ISFINITE(altitude) && ((altitude > -12'000.f) && (altitude < 100'000.f))); - const bool epv_valid = (PX4_ISFINITE(epv) && (epv >= 0.f)); - - return alt_valid && epv_valid; + 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, @@ -105,7 +101,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const float eph) { - if (!checkLatLonValidity(latitude, longitude, eph)) { + if (!checkLatLonValidity(latitude, longitude)) { return false; } @@ -121,7 +117,10 @@ bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const f // reinitialize map projection to latitude, longitude, altitude, and reset position _pos_ref.initReference(latitude, longitude, _time_delayed_us); - _gpos_origin_eph = eph; + + if (PX4_ISFINITE(eph) && (eph >= 0.f)) { + _gpos_origin_eph = eph; + } _NED_origin_initialised = true; @@ -136,13 +135,16 @@ bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const f bool Ekf::setAltOrigin(const float altitude, const float epv) { - if (!checkAltitudeValidity(altitude, epv)) { + if (!checkAltitudeValidity(altitude)) { return false; } const float gps_alt_ref_prev = _gps_alt_ref; _gps_alt_ref = altitude; - _gpos_origin_epv = epv; + + if (PX4_ISFINITE(epv) && (epv >= 0.f)) { + _gpos_origin_epv = epv; + } if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { // determine current z @@ -163,6 +165,59 @@ bool Ekf::setAltOrigin(const float altitude, const float epv) return true; } +bool Ekf::setEkfGlobalOriginFromCurrentPos(const double latitude, const double longitude, const float altitude, + const float eph, const float epv) +{ + if (!setLatLonOriginFromCurrentPos(latitude, longitude, eph)) { + return false; + } + + // altitude is optional + setAltOriginFromCurrentPos(altitude, epv); + + return true; +} + +bool Ekf::setLatLonOriginFromCurrentPos(const double latitude, const double longitude, const float eph) +{ + if (!checkLatLonValidity(latitude, longitude)) { + return false; + } + + _pos_ref.initReference(latitude, longitude, _time_delayed_us); + + // if we are already doing aiding, correct for the change in position since the EKF started navigating + if (isHorizontalAidingActive()) { + 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); + } + + if (PX4_ISFINITE(eph) && (eph >= 0.f)) { + _gpos_origin_eph = eph; + } + + _NED_origin_initialised = true; + + return true; +} + +bool Ekf::setAltOriginFromCurrentPos(const float altitude, const float epv) +{ + if (!checkAltitudeValidity(altitude)) { + return false; + } + + _gps_alt_ref = altitude + _state.pos(2); + + if (PX4_ISFINITE(epv) && (epv >= 0.f)) { + _gpos_origin_epv = epv; + } + + return true; +} + void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const { float eph = INFINITY; From 130fefb1e7f3fc3d9948cd49adf7ac19ca28fc9d Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 21 Aug 2024 16:32:29 +0200 Subject: [PATCH 11/31] ekf2: initialize origin from corrent position when possible --- .../aid_sources/aux_global_position/aux_global_position.cpp | 3 ++- src/modules/ekf2/EKF/ekf.cpp | 3 +-- 2 files changed, 3 insertions(+), 3 deletions(-) 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 6efd4fabe66b..dc8f318c9778 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 @@ -113,7 +113,8 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed } else { // Try to initialize using measurement - if (ekf.setEkfGlobalOrigin(sample.latitude, sample.longitude, sample.altitude_amsl, sample.eph, sample.epv)) { + if (ekf.setEkfGlobalOriginFromCurrentPos(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; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 9f6a0ab40b66..a81cc39d6294 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -280,8 +280,7 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl uint64_t timestamp_observation) { if (!_pos_ref.isInitialized()) { - ECL_WARN("unable to reset global position, position reference not initialized"); - return false; + return setLatLonOriginFromCurrentPos(lat_deg, lon_deg, accuracy); } Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg); From cd2170deea5d7b2bb387ddc3ba7a7c3abd58b133 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 26 Aug 2024 11:53:40 +0200 Subject: [PATCH 12/31] ekf2-origin: backcompute based on lpos validity --- src/modules/ekf2/EKF/ekf_helper.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 6e3bdf3bab45..f33cbcd5bc43 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -110,7 +110,7 @@ bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const f double current_lon = static_cast(NAN); // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { + if (_pos_ref.isInitialized() && local_position_is_valid()) { _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); current_pos_available = true; } @@ -146,7 +146,7 @@ bool Ekf::setAltOrigin(const float altitude, const float epv) _gpos_origin_epv = epv; } - if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { + 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; @@ -187,7 +187,7 @@ bool Ekf::setLatLonOriginFromCurrentPos(const double latitude, const double long _pos_ref.initReference(latitude, longitude, _time_delayed_us); // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (isHorizontalAidingActive()) { + if (local_position_is_valid()) { double est_lat; double est_lon; _pos_ref.reproject(-_state.pos(0), -_state.pos(1), est_lat, est_lon); From bab256bfe6ae496f1438c685693e0cc90d091ade Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 23 Aug 2024 15:33:21 +0200 Subject: [PATCH 13/31] ekf2: handle external altitude resets --- src/modules/ekf2/EKF/ekf.cpp | 97 ++++++++++++++------- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF2.cpp | 5 +- src/modules/ekf2/test/CMakeLists.txt | 2 +- src/modules/ekf2/test/test_EKF_airspeed.cpp | 79 ++++++++++++++++- 5 files changed, 147 insertions(+), 38 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index a81cc39d6294..24734dcfb370 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -276,67 +276,100 @@ void Ekf::predictState(const imuSample &imu_delayed) _height_rate_lpf = _height_rate_lpf * (1.0f - alpha_height_rate_lpf) + _state.vel(2) * alpha_height_rate_lpf; } -bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, - uint64_t timestamp_observation) +bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const double longitude, const float altitude, + const float eph, + const float epv, uint64_t timestamp_observation) { + if (!checkLatLonValidity(latitude, longitude)) { + return false; + } + if (!_pos_ref.isInitialized()) { - return setLatLonOriginFromCurrentPos(lat_deg, lon_deg, accuracy); + if (!setLatLonOriginFromCurrentPos(latitude, longitude, eph)) { + return false; + } + + if (!PX4_ISFINITE(_gps_alt_ref)) { + setAltOriginFromCurrentPos(altitude, epv); + } + + return true; } - Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg); + Vector3f pos_correction; // apply a first order correction using velocity at the delayed time horizon and the delta time - if ((timestamp_observation > 0) && (isHorizontalAidingActive() || !_horizontal_deadreckon_time_exceeded)) { + if ((timestamp_observation > 0) && local_position_is_valid()) { timestamp_observation = math::min(_time_latest_us, timestamp_observation); - float diff_us = 0.f; + float dt_us; if (_time_delayed_us >= timestamp_observation) { - diff_us = static_cast(_time_delayed_us - timestamp_observation); + dt_us = static_cast(_time_delayed_us - timestamp_observation); } else { - diff_us = -static_cast(timestamp_observation - _time_delayed_us); + dt_us = -static_cast(timestamp_observation - _time_delayed_us); } - const float dt_s = diff_us * 1e-6f; - pos_corrected += _state.vel.xy() * dt_s; + const float dt_s = dt_us * 1e-6f; + pos_correction = _state.vel * dt_s; } - const float obs_var = math::max(sq(accuracy), sq(0.01f)); + { + const Vector2f hpos = _pos_ref.project(latitude, longitude) + pos_correction.xy(); - const Vector2f innov = Vector2f(_state.pos.xy()) - pos_corrected; - const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; + const float obs_var = math::max(sq(eph), sq(0.01f)); - const float sq_gate = sq(5.f); // magic hardcoded gate - const Vector2f test_ratio{sq(innov(0)) / (sq_gate * innov_var(0)), - sq(innov(1)) / (sq_gate * innov_var(1))}; + const Vector2f innov = Vector2f(_state.pos.xy()) - hpos; + const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; - const bool innov_rejected = (test_ratio.max() > 1.f); + const float sq_gate = sq(5.f); // magic hardcoded gate + const float test_ratio = sq(innov(0)) / (sq_gate * innov_var(0)) + sq(innov(1)) / (sq_gate * innov_var(1)); - if (!_control_status.flags.in_air || (accuracy > 0.f && accuracy < 1.f) || innov_rejected) { - // when on ground or accuracy chosen to be very low, we hard reset position - // this allows the user to still send hard resets at any time - ECL_INFO("reset position to external observation"); - _information_events.flags.reset_pos_to_ext_obs = true; + const bool innov_rejected = (test_ratio > 1.f); - resetHorizontalPositionTo(pos_corrected, obs_var); - _last_known_pos.xy() = _state.pos.xy(); - return true; + if (!_control_status.flags.in_air || (eph > 0.f && eph < 1.f) || innov_rejected) { + // when on ground or accuracy chosen to be very low, we hard reset position + // this allows the user to still send hard resets at any time + ECL_INFO("reset position to external observation"); + _information_events.flags.reset_pos_to_ext_obs = true; - } else { - if (fuseDirectStateMeasurement(innov(0), innov_var(0), obs_var, State::pos.idx + 0) - && fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1) - ) { - ECL_INFO("fused external observation as position measurement"); + resetHorizontalPositionTo(hpos, obs_var); + _last_known_pos.xy() = _state.pos.xy(); + + } else { + ECL_INFO("fuse external observation as position measurement"); + fuseDirectStateMeasurement(innov(0), innov_var(0), obs_var, State::pos.idx + 0); + fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1); + + // Use the reset counters to inform the controllers about a potential large position jump + // TODO: compute the actual position change _state_reset_status.reset_count.posNE++; + _state_reset_status.posNE_change.zero(); + _time_last_hor_pos_fuse = _time_delayed_us; _last_known_pos.xy() = _state.pos.xy(); - return true; } } - return false; + if (checkAltitudeValidity(altitude)) { + const float altitude_corrected = altitude - pos_correction(2); + + if (!PX4_ISFINITE(_gps_alt_ref)) { + setAltOriginFromCurrentPos(altitude_corrected, epv); + + } 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); + } + } + + return true; } void Ekf::updateParameters() diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 5f2ba8c95fb4..5be5cee3bbad 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -533,7 +533,7 @@ class Ekf final : public EstimatorInterface return true; } - bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, + bool resetGlobalPosToExternalObservation(double latitude, double longitude, float altitude, float eph, float epv, uint64_t timestamp_observation); /** diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index c339548b8cef..7769543d2bbd 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -545,9 +545,8 @@ void EKF2::Run() accuracy = vehicle_command.param3; } - // TODO add check for lat and long validity - if (_ekf.resetGlobalPosToExternalObservation(vehicle_command.param5, vehicle_command.param6, - accuracy, timestamp_observation) + if (_ekf.resetGlobalPosToExternalObservation(vehicle_command.param5, vehicle_command.param6, vehicle_command.param7, + accuracy, accuracy, timestamp_observation) ) { command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index c1ecb992b99b..7e200c4c54ab 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -37,7 +37,7 @@ add_subdirectory(sensor_simulator) add_subdirectory(test_helper) px4_add_unit_gtest(SRC test_EKF_accelerometer.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_fake_pos.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) diff --git a/src/modules/ekf2/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp index d1bd54a13b21..b9dc3e367279 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -40,6 +40,7 @@ #include "EKF/ekf.h" #include "sensor_simulator/sensor_simulator.h" #include "sensor_simulator/ekf_wrapper.h" +#include "test_helper/reset_logging_checker.h" class EkfAirspeedTest : public ::testing::Test @@ -182,9 +183,11 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) 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, 50.f, 0); + _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); // Simulate the fact that the sideslip can start immediately, without // waiting for a measurement sample. @@ -203,4 +206,78 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) const Vector2f vel_wind_earth = _ekf->getWindVelocity(); EXPECT_NEAR(vel_wind_earth(0), 0.f, .1f); EXPECT_NEAR(vel_wind_earth(1), 0.f, .1f); + + EXPECT_TRUE(_ekf->global_position_is_valid()); +} + +TEST_F(EkfAirspeedTest, testAirspeedDeadReckoningLatLonAltReset) +{ + // GIVEN: a flying fixed-wing dead-reckoning with airspeed and sideslip fusion + const Vector3f simulated_velocity_earth(-3.6f, 8.f, 0.0f); + const Vector2f airspeed_body(15.f, 0.0f); + _sensor_simulator.runSeconds(10); + + _ekf->set_in_air_status(true); + _ekf->set_vehicle_at_rest(false); + _ekf->set_is_fixed_wing(true); + + double latitude = -15.0000005; + double longitude = -115.0000005; + float altitude = 1500.0; + 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(); + _sensor_simulator.runSeconds(1.f); + EXPECT_TRUE(_ekf_wrapper.isIntendingBetaFusion()); + + _sensor_simulator.startAirspeedSensor(); + _sensor_simulator._airspeed.setData(airspeed_body(0), airspeed_body(0)); + _sensor_simulator.runSeconds(10.f); + EXPECT_TRUE(_ekf_wrapper.isIntendingAirspeedFusion()); + + EXPECT_TRUE(_ekf->global_position_is_valid()); + + // WHEN: an external position reset is sent + ResetLoggingChecker reset_logging_checker(_ekf); + reset_logging_checker.capturePreResetState(); + + double latitude_new = -16.0000005; + double longitude_new = -116.0000005; + float altitude_new = 1602.0; + _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); + + const Vector3f pos_new = _ekf->getPosition(); + const float altitude_est = -pos_new(2) + _ekf->getEkfGlobalOriginAltitude(); + + double latitude_est, longitude_est; + _ekf->global_origin().reproject(pos_new(0), pos_new(1), latitude_est, longitude_est); + + // THEN: the global position is adjusted accordingly + EXPECT_NEAR(altitude_est, altitude_new, 0.01f); + EXPECT_NEAR(latitude_est, latitude_new, 1e-3f); + EXPECT_NEAR(longitude_est, longitude_new, 1e-3f); + EXPECT_TRUE(_ekf->global_position_is_valid()); + + reset_logging_checker.capturePostResetState(); + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); + EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(1)); + + // AND WHEN: only the lat/lon is valid + latitude_new = -16.0000005; + longitude_new = -116.0000005; + altitude_new = NAN; + _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); + + // THEN: lat/lon are reset but not the altitude + reset_logging_checker.capturePostResetState(); + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); + EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(2)); } From 0f1507c24e549f165dd3c7f70ab1b996854276f4 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 28 Aug 2024 07:23:39 -0800 Subject: [PATCH 14/31] [gz] X500 mono_cam_down and aruco world (#23450) * x500 mono cam down and aruco world * remove duplicate line --- .../init.d-posix/airframes/4014_gz_x500_mono_cam_down | 10 ++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + src/modules/simulation/gz_bridge/CMakeLists.txt | 1 + 3 files changed, 12 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down new file mode 100644 index 000000000000..199e4ecff380 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down @@ -0,0 +1,10 @@ +#!/bin/sh +# +# @name Gazebo x500 mono cam +# +# @type Quadrotor +# + +PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_mono_cam_down} + +. ${R}etc/init.d-posix/airframes/4001_gz_x500 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 9235b2e66340..d53330cec1b8 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -85,6 +85,7 @@ px4_add_romfs_files( 4011_gz_lawnmower 4012_gz_rover_ackermann 4013_gz_x500_lidar + 4014_gz_x500_mono_cam_down 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index c7d36e36a5ad..0d1e8eed66fd 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -94,6 +94,7 @@ if(gz-transport_FOUND) baylands lawn rover + aruco ) # find corresponding airframes From 2cda0efd84811d8ebdd4bdce45b0f6bb618a081d Mon Sep 17 00:00:00 2001 From: Mathieu Bresciani Date: Wed, 28 Aug 2024 17:33:58 +0200 Subject: [PATCH 15/31] Commander: extend COM_ARM_WO_GPS to disable warning (#23628) --- .../checks/estimatorCheck.cpp | 36 +++++++++++++++---- .../checks/estimatorCheck.hpp | 8 ++++- src/modules/commander/commander_params.c | 9 +++-- 3 files changed, 43 insertions(+), 10 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 2b7c45318301..aa400e27c1ae 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -273,12 +273,27 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor } if (!context.isArmed() && ekf_gps_check_fail) { - NavModes required_groups_gps = required_groups; - events::Log log_level = events::Log::Error; + NavModes required_groups_gps; + events::Log log_level; - if (_param_com_arm_wo_gps.get()) { + switch (static_cast(_param_com_arm_wo_gps.get())) { + default: + + /* FALLTHROUGH */ + case GnssArmingCheck::DenyArming: + required_groups_gps = required_groups; + log_level = events::Log::Error; + break; + + case GnssArmingCheck::WarningOnly: required_groups_gps = NavModes::None; // optional log_level = events::Log::Warning; + break; + + case GnssArmingCheck::Disabled: + required_groups_gps = NavModes::None; + log_level = events::Log::Disabled; + break; } // Only report the first failure to avoid spamming @@ -438,11 +453,20 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor } if (message && reporter.mavlink_log_pub()) { - if (!_param_com_arm_wo_gps.get()) { + switch (static_cast(_param_com_arm_wo_gps.get())) { + default: + + /* FALLTHROUGH */ + case GnssArmingCheck::DenyArming: mavlink_log_critical(reporter.mavlink_log_pub(), message, " Fail"); + break; - } else { - mavlink_log_critical(reporter.mavlink_log_pub(), message, ""); + case GnssArmingCheck::WarningOnly: + mavlink_log_warning(reporter.mavlink_log_pub(), message, ""); + break; + + case GnssArmingCheck::Disabled: + break; } } } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index 4f61df88670f..d5cb363e1130 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -59,6 +59,12 @@ class EstimatorChecks : public HealthAndArmingCheckBase void checkAndReport(const Context &context, Report &reporter) override; private: + enum class GnssArmingCheck : uint8_t { + DenyArming = 0, + WarningOnly = 1, + Disabled = 2 + }; + void checkEstimatorStatus(const Context &context, Report &reporter, const estimator_status_s &estimator_status, NavModes required_groups); void checkSensorBias(const Context &context, Report &reporter, NavModes required_groups); @@ -108,7 +114,7 @@ class EstimatorChecks : public HealthAndArmingCheckBase DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, (ParamInt) _param_sens_imu_mode, (ParamInt) _param_com_arm_mag_str, - (ParamBool) _param_com_arm_wo_gps, + (ParamInt) _param_com_arm_wo_gps, (ParamBool) _param_sys_has_gps, (ParamFloat) _param_com_pos_fs_eph, (ParamFloat) _param_com_vel_fs_evh, diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index a462c8ae898c..0b20831a6eab 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -225,11 +225,14 @@ PARAM_DEFINE_FLOAT(COM_DISARM_LAND, 2.0f); PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 10.0f); /** - * Allow arming without GPS + * GPS preflight check + * + * Measures taken when a check defined by EKF2_GPS_CHECK is failing. * * @group Commander - * @value 0 Require GPS lock to arm - * @value 1 Allow arming without GPS + * @value 0 Deny arming + * @value 1 Warning only + * @value 2 Disabled */ PARAM_DEFINE_INT32(COM_ARM_WO_GPS, 1); From 6b3e3aa363f2cf8425fa06d8e7db4d30422d1886 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 14 Aug 2024 14:45:50 +0200 Subject: [PATCH 16/31] Commander: improve param description of COM_POSCTL_NAVL and rename Manual-->Stabilized Signed-off-by: Silvan Fuhrer --- src/modules/commander/commander_params.c | 28 +++++++++------------ src/modules/commander/failsafe/failsafe.cpp | 2 +- src/modules/commander/failsafe/failsafe.h | 2 +- 3 files changed, 14 insertions(+), 18 deletions(-) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 0b20831a6eab..72dadca8fa42 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -338,14 +338,14 @@ PARAM_DEFINE_INT32(COM_QC_ACT, 0); * The offboard loss failsafe will only be entered after a timeout, * set by COM_OF_LOSS_T in seconds. * - * @value 0 Position mode - * @value 1 Altitude mode - * @value 2 Manual - * @value 3 Return mode - * @value 4 Land mode - * @value 5 Hold mode - * @value 6 Terminate - * @value 7 Disarm + * @value 0 Position mode + * @value 1 Altitude mode + * @value 2 Stabilized + * @value 3 Return mode + * @value 4 Land mode + * @value 5 Hold mode + * @value 6 Terminate + * @value 7 Disarm * @group Commander */ PARAM_DEFINE_INT32(COM_OBL_RC_ACT, 0); @@ -453,16 +453,12 @@ PARAM_DEFINE_FLOAT(COM_RC_STICK_OV, 30.0f); PARAM_DEFINE_INT32(COM_ARM_MIS_REQ, 0); /** - * Position control navigation loss response. - * - * This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. - * - * If Altitude/Manual is selected: assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. + * Position mode navigation loss response * - * If Land/Descend is selected: assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to Descend. + * This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode. * - * @value 0 Altitude/Manual - * @value 1 Land/Descend + * @value 0 Altitude mode + * @value 1 Land mode (descend) * * @group Commander */ diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index f868d6740835..926bdfe44d94 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -292,7 +292,7 @@ FailsafeBase::Action Failsafe::fromOffboardLossActParam(int param_value, uint8_t user_intended_mode = vehicle_status_s::NAVIGATION_STATE_ALTCTL; break; - case offboard_loss_failsafe_mode::Manual: + case offboard_loss_failsafe_mode::Stabilized: action = Action::FallbackStab; user_intended_mode = vehicle_status_s::NAVIGATION_STATE_STAB; break; diff --git a/src/modules/commander/failsafe/failsafe.h b/src/modules/commander/failsafe/failsafe.h index 1c1b8bd86562..742b84ce36e5 100644 --- a/src/modules/commander/failsafe/failsafe.h +++ b/src/modules/commander/failsafe/failsafe.h @@ -70,7 +70,7 @@ class Failsafe : public FailsafeBase enum class offboard_loss_failsafe_mode : int32_t { Position_mode = 0, Altitude_mode = 1, - Manual = 2, + Stabilized = 2, Return_mode = 3, Land_mode = 4, Hold_mode = 5, From c86d44f831185ba6013c631fb8528e00e7d64593 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 14 Aug 2024 14:46:32 +0200 Subject: [PATCH 17/31] Commander: remove 2 decimals from COM_FAIL_ACT_T Signed-off-by: Silvan Fuhrer --- src/modules/commander/commander_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 72dadca8fa42..8c947719306a 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -288,7 +288,7 @@ PARAM_DEFINE_INT32(COM_LOW_BAT_ACT, 0); * @unit s * @min 0.0 * @max 25.0 - * @decimal 3 + * @decimal 1 */ PARAM_DEFINE_FLOAT(COM_FAIL_ACT_T, 5.f); From f8188f0981a12bfd576854900c3e160f693ceef6 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Thu, 29 Aug 2024 15:27:08 +0200 Subject: [PATCH 18/31] differential: update module (#23629) Improve the slow down effect and add support for speed change in mission mode. Seperate code related to turning setpoints into motor commands into its own folder and refactor code. --- .../init.d-posix/airframes/4009_gz_r1_rover | 12 +- .../init.d-posix/airframes/4011_gz_lawnmower | 4 +- .../airframes/50001_aion_robotics_r1_rover | 22 ++ msg/CMakeLists.txt | 1 + msg/RoverDifferentialGuidanceStatus.msg | 3 - msg/RoverDifferentialSetpoint.msg | 9 + msg/RoverDifferentialStatus.msg | 7 +- src/modules/logger/logged_topics.cpp | 1 + src/modules/rover_differential/CMakeLists.txt | 5 +- .../rover_differential/RoverDifferential.cpp | 172 ++++++-------- .../rover_differential/RoverDifferential.hpp | 43 ++-- .../RoverDifferentialControl/CMakeLists.txt | 39 ++++ .../RoverDifferentialControl.cpp | 176 +++++++++++++++ .../RoverDifferentialControl.hpp | 121 ++++++++++ .../RoverDifferentialGuidance/CMakeLists.txt | 1 - .../RoverDifferentialGuidance.cpp | 209 ++++++++---------- .../RoverDifferentialGuidance.hpp | 55 ++--- src/modules/rover_differential/module.yaml | 49 ++-- 18 files changed, 603 insertions(+), 326 deletions(-) create mode 100644 msg/RoverDifferentialSetpoint.msg create mode 100644 src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt create mode 100644 src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp create mode 100644 src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover index 7697e23db769..26429add58e5 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover @@ -14,15 +14,17 @@ param set-default SIM_GZ_EN 1 # Gazebo bridge # Rover parameters param set-default RD_WHEEL_TRACK 0.3 param set-default RD_MAN_YAW_SCALE 0.1 -param set-default RD_YAW_RATE_I 0.1 -param set-default RD_YAW_RATE_P 5 param set-default RD_MAX_ACCEL 6 param set-default RD_MAX_JERK 30 param set-default RD_MAX_SPEED 7 -param set-default RD_HEADING_P 5 -param set-default RD_HEADING_I 0.1 +param set-default RD_YAW_RATE_P 5 +param set-default RD_YAW_RATE_I 0 +param set-default RD_YAW_P 5 +param set-default RD_YAW_I 0 +param set-default RD_SPEED_P 1 +param set-default RD_SPEED_I 0 param set-default RD_MAX_YAW_RATE 180 -param set-default RD_MISS_SPD_DEF 7 +param set-default RD_MISS_SPD_DEF 5 param set-default RD_TRANS_DRV_TRN 0.349066 param set-default RD_TRANS_TRN_DRV 0.174533 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower b/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower index c0d91e222365..8a05e2a15e52 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower @@ -27,8 +27,8 @@ param set-default RD_YAW_RATE_P 5 param set-default RD_MAX_ACCEL 1 param set-default RD_MAX_JERK 3 param set-default RD_MAX_SPEED 8 -param set-default RD_HEADING_P 5 -param set-default RD_HEADING_I 0.1 +param set-default RD_YAW_P 5 +param set-default RD_YAW_I 0.1 param set-default RD_MAX_YAW_RATE 30 param set-default RD_MISS_SPD_DEF 8 param set-default RD_TRANS_DRV_TRN 0.349066 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover index c06b158cf857..1ea26ad6bff0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover @@ -20,3 +20,25 @@ param set-default RBCLW_ADDRESS 128 param set-default RBCLW_FUNC1 101 param set-default RBCLW_FUNC2 102 param set-default RBCLW_REV 1 # reverse right wheels + +# Rover parameters +param set-default RD_WHEEL_TRACK 0.3 +param set-default RD_MAN_YAW_SCALE 1 +param set-default RD_MAX_ACCEL 5 +param set-default RD_MAX_JERK 50 +param set-default RD_MAX_SPEED 2 +param set-default RD_YAW_RATE_P 0.1 +param set-default RD_YAW_RATE_I 0 +param set-default RD_YAW_P 5 +param set-default RD_YAW_I 0 +param set-default RD_SPEED_P 0.5 +param set-default RD_SPEED_I 0.1 +param set-default RD_MAX_YAW_RATE 300 +param set-default RD_MISS_SPD_DEF 1.8 +param set-default RD_TRANS_DRV_TRN 0.349066 +param set-default RD_TRANS_TRN_DRV 0.174533 + +# Pure pursuit parameters +param set-default PP_LOOKAHD_MAX 10 +param set-default PP_LOOKAHD_MIN 1 +param set-default PP_LOOKAHD_GAIN 1 diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 3b31b7de554d..dce7e851dca9 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -182,6 +182,7 @@ set(msg_files RoverAckermannGuidanceStatus.msg RoverAckermannStatus.msg RoverDifferentialGuidanceStatus.msg + RoverDifferentialSetpoint.msg RoverDifferentialStatus.msg Rpm.msg RtlStatus.msg diff --git a/msg/RoverDifferentialGuidanceStatus.msg b/msg/RoverDifferentialGuidanceStatus.msg index 836546e7ebb7..ce3d37511163 100644 --- a/msg/RoverDifferentialGuidanceStatus.msg +++ b/msg/RoverDifferentialGuidanceStatus.msg @@ -1,10 +1,7 @@ uint64 timestamp # time since system start (microseconds) -float32 desired_speed # [m/s] Desired forward speed for the rover float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller float32 heading_error_deg # [deg] Heading error of the pure pursuit controller -float32 pid_heading_integral # Integral of the PID for the desired yaw rate during missions -float32 pid_throttle_integral # Integral of the PID for the throttle during missions uint8 state_machine # Driving state of the rover [0: SPOT_TURNING, 1: DRIVING, 2: GOAL_REACHED] # TOPICS rover_differential_guidance_status diff --git a/msg/RoverDifferentialSetpoint.msg b/msg/RoverDifferentialSetpoint.msg new file mode 100644 index 000000000000..b16f712828d8 --- /dev/null +++ b/msg/RoverDifferentialSetpoint.msg @@ -0,0 +1,9 @@ +uint64 timestamp # time since system start (microseconds) + +float32 forward_speed_setpoint # [m/s] Desired forward speed for the rover +float32 forward_speed_setpoint_normalized # [-1, 1] Normalized forward speed for the rover +float32 yaw_rate_setpoint # [rad/s] Desired yaw rate for the rover (Overriden by yaw controller if yaw_setpoint is used) +float32 yaw_rate_setpoint_normalized # [-1, 1] Normalized yaw rate for the rover +float32 yaw_setpoint # [rad] Desired yaw (heading) for the rover + +# TOPICS rover_differential_setpoint diff --git a/msg/RoverDifferentialStatus.msg b/msg/RoverDifferentialStatus.msg index 31907ffa6477..4d3d54eb9909 100644 --- a/msg/RoverDifferentialStatus.msg +++ b/msg/RoverDifferentialStatus.msg @@ -1,8 +1,11 @@ uint64 timestamp # time since system start (microseconds) float32 actual_speed # [m/s] Actual forward speed of the rover -float32 desired_yaw_rate_deg_s # [deg/s] Desired yaw rate +float32 actual_yaw_deg # [deg] Actual yaw of the rover float32 actual_yaw_rate_deg_s # [deg/s] Actual yaw rate of the rover -float32 pid_yaw_rate_integral # Integral of the PID for the desired yaw rate controller +float32 desired_yaw_rate_deg_s # [deg/s] Yaw rate setpoint for the closed loop yaw rate controller +float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller +float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller +float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller # TOPICS rover_differential_status diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 5be39234e34f..f5ce636c23c9 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -105,6 +105,7 @@ void LoggedTopics::add_default_topics() add_optional_topic("rover_ackermann_guidance_status", 100); add_optional_topic("rover_ackermann_status", 100); add_optional_topic("rover_differential_guidance_status", 100); + add_optional_topic("rover_differential_setpoint", 100); add_optional_topic("rover_differential_status", 100); add_topic("rtl_time_estimate", 1000); add_topic("rtl_status", 2000); diff --git a/src/modules/rover_differential/CMakeLists.txt b/src/modules/rover_differential/CMakeLists.txt index beaec32a8776..880589316074 100644 --- a/src/modules/rover_differential/CMakeLists.txt +++ b/src/modules/rover_differential/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. +# 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 @@ -32,6 +32,7 @@ ############################################################################ add_subdirectory(RoverDifferentialGuidance) +add_subdirectory(RoverDifferentialControl) px4_add_module( MODULE modules__rover_differential @@ -41,8 +42,8 @@ px4_add_module( RoverDifferential.hpp DEPENDS RoverDifferentialGuidance + RoverDifferentialControl px4_work_queue - modules__control_allocator # for parameter CA_R_REV pure_pursuit MODULE_CONFIG module.yaml diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index ab89392a0ec8..20cbf7d9e3e2 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -32,16 +32,13 @@ ****************************************************************************/ #include "RoverDifferential.hpp" -using namespace matrix; -using namespace time_literals; RoverDifferential::RoverDifferential() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) { updateParams(); - _rover_differential_status_pub.advertise(); - pid_init(&_pid_yaw_rate, PID_MODE_DERIVATIV_NONE, 0.001f); + _rover_differential_setpoint_pub.advertise(); } bool RoverDifferential::init() @@ -53,16 +50,7 @@ bool RoverDifferential::init() void RoverDifferential::updateParams() { ModuleParams::updateParams(); - _max_yaw_rate = _param_rd_max_yaw_rate.get() * M_DEG_TO_RAD_F; - - pid_set_parameters(&_pid_yaw_rate, - _param_rd_p_gain_yaw_rate.get(), // Proportional gain - _param_rd_i_gain_yaw_rate.get(), // Integral gain - 0.f, // Derivative gain - 1.f, // Integral limit - 1.f); // Output limit - } void RoverDifferential::Run() @@ -73,135 +61,99 @@ void RoverDifferential::Run() return; } - hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - // uORB subscriber updates - if (_parameter_update_sub.updated()) { - parameter_update_s parameter_update; - _parameter_update_sub.copy(¶meter_update); - updateParams(); - } + updateSubscriptions(); - if (_vehicle_status_sub.updated()) { - vehicle_status_s vehicle_status{}; - _vehicle_status_sub.copy(&vehicle_status); - _nav_state = vehicle_status.nav_state; - } + // Generate and publish attitude and velocity setpoints + hrt_abstime timestamp = hrt_absolute_time(); - if (_vehicle_angular_velocity_sub.updated()) { - vehicle_angular_velocity_s vehicle_angular_velocity{}; - _vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity); - _vehicle_body_yaw_rate = vehicle_angular_velocity.xyz[2]; - } - - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); - } - - if (_vehicle_local_position_sub.updated()) { - vehicle_local_position_s vehicle_local_position{}; - _vehicle_local_position_sub.copy(&vehicle_local_position); - Vector3f velocity_in_local_frame(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz); - Vector3f velocity_in_body_frame = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_in_local_frame); - _vehicle_forward_speed = velocity_in_body_frame(0); - } - - // Navigation modes switch (_nav_state) { case vehicle_status_s::NAVIGATION_STATE_MANUAL: { manual_control_setpoint_s manual_control_setpoint{}; if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - _differential_setpoint.throttle = manual_control_setpoint.throttle; - _differential_setpoint.yaw_rate = manual_control_setpoint.roll * _param_rd_man_yaw_scale.get(); - + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.timestamp = timestamp; + rover_differential_setpoint.forward_speed_setpoint = NAN; + rover_differential_setpoint.forward_speed_setpoint_normalized = manual_control_setpoint.throttle; + rover_differential_setpoint.yaw_setpoint = NAN; + rover_differential_setpoint.yaw_rate_setpoint_normalized = manual_control_setpoint.roll * _param_rd_man_yaw_scale.get(); + rover_differential_setpoint.yaw_rate_setpoint = NAN; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); } - - _differential_setpoint.closed_loop_yaw_rate = false; } break; case vehicle_status_s::NAVIGATION_STATE_ACRO: { manual_control_setpoint_s manual_control_setpoint{}; if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - _differential_setpoint.throttle = manual_control_setpoint.throttle; - _differential_setpoint.yaw_rate = math::interpolate(manual_control_setpoint.roll, - -1.f, 1.f, - -_max_yaw_rate, _max_yaw_rate); + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.timestamp = timestamp; + rover_differential_setpoint.forward_speed_setpoint = NAN; + rover_differential_setpoint.forward_speed_setpoint_normalized = manual_control_setpoint.throttle; + rover_differential_setpoint.yaw_rate_setpoint = math::interpolate(manual_control_setpoint.roll, + -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); + rover_differential_setpoint.yaw_rate_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_setpoint = NAN; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); } - _differential_setpoint.closed_loop_yaw_rate = true; } break; case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: - _differential_setpoint = _rover_differential_guidance.computeGuidance(_vehicle_yaw, _vehicle_forward_speed, - _nav_state); + _rover_differential_guidance.computeGuidance(_vehicle_yaw, _vehicle_forward_speed, _nav_state); break; default: // Unimplemented nav states will stop the rover - _differential_setpoint.throttle = 0.f; - _differential_setpoint.yaw_rate = 0.f; - _differential_setpoint.closed_loop_yaw_rate = false; + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.forward_speed_setpoint = NAN; + rover_differential_setpoint.forward_speed_setpoint_normalized = 0.f; + rover_differential_setpoint.yaw_rate_setpoint = NAN; + rover_differential_setpoint.yaw_rate_setpoint_normalized = 0.f; + rover_differential_setpoint.yaw_setpoint = NAN; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); break; } - float speed_diff_normalized = _differential_setpoint.yaw_rate; - - // Closed loop yaw rate control - if (_differential_setpoint.closed_loop_yaw_rate) { - if (fabsf(_differential_setpoint.yaw_rate - _vehicle_body_yaw_rate) < YAW_RATE_ERROR_THRESHOLD) { - speed_diff_normalized = 0.f; - pid_reset_integral(&_pid_yaw_rate); - - } else { - const float speed_diff = _differential_setpoint.yaw_rate * _param_rd_wheel_track.get(); // Feedforward - speed_diff_normalized = math::interpolate(speed_diff, -_param_rd_max_speed.get(), - _param_rd_max_speed.get(), -1.f, 1.f); - speed_diff_normalized = math::constrain(speed_diff_normalized + - pid_calculate(&_pid_yaw_rate, _differential_setpoint.yaw_rate, _vehicle_body_yaw_rate, 0, dt), - -1.f, 1.f); // Feedback - } - - } else { - pid_reset_integral(&_pid_yaw_rate); - } - - // Publish rover differential status (logging) - rover_differential_status_s rover_differential_status{}; - rover_differential_status.timestamp = _timestamp; - rover_differential_status.actual_speed = _vehicle_forward_speed; - rover_differential_status.desired_yaw_rate_deg_s = M_RAD_TO_DEG_F * _differential_setpoint.yaw_rate; - rover_differential_status.actual_yaw_rate_deg_s = M_RAD_TO_DEG_F * _vehicle_body_yaw_rate; - rover_differential_status.pid_yaw_rate_integral = _pid_yaw_rate.integral; - _rover_differential_status_pub.publish(rover_differential_status); - - // Publish to motors - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - computeMotorCommands(_differential_setpoint.throttle, speed_diff_normalized).copyTo(actuator_motors.control); - actuator_motors.timestamp = _timestamp; - _actuator_motors_pub.publish(actuator_motors); + _rover_differential_control.computeMotorCommands(_vehicle_yaw, _vehicle_yaw_rate, _vehicle_forward_speed); } -matrix::Vector2f RoverDifferential::computeMotorCommands(float forward_speed, const float speed_diff) +void RoverDifferential::updateSubscriptions() { - float combined_velocity = fabsf(forward_speed) + fabsf(speed_diff); - if (combined_velocity > 1.0f) { // Prioritize yaw rate - float excess_velocity = fabsf(combined_velocity - 1.0f); - forward_speed -= sign(forward_speed) * excess_velocity; + if (_parameter_update_sub.updated()) { + parameter_update_s parameter_update; + _parameter_update_sub.copy(¶meter_update); + updateParams(); + } + + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status{}; + _vehicle_status_sub.copy(&vehicle_status); + _nav_state = vehicle_status.nav_state; } - // Calculate the left and right wheel speeds - return Vector2f(forward_speed - speed_diff, - forward_speed + speed_diff); + if (_vehicle_angular_velocity_sub.updated()) { + vehicle_angular_velocity_s vehicle_angular_velocity{}; + _vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity); + _vehicle_yaw_rate = vehicle_angular_velocity.xyz[2]; + } + + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _vehicle_local_position_sub.copy(&vehicle_local_position); + Vector3f velocity_in_local_frame(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz); + Vector3f velocity_in_body_frame = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_in_local_frame); + _vehicle_forward_speed = velocity_in_body_frame(0); + } } int RoverDifferential::task_spawn(int argc, char *argv[]) diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index 3dafe99b0566..897a7199ef4d 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -42,23 +42,21 @@ // uORB includes #include -#include #include #include #include #include -#include #include #include #include -#include +#include // Standard libraries -#include #include // Local includes #include "RoverDifferentialGuidance/RoverDifferentialGuidance.hpp" +#include "RoverDifferentialControl/RoverDifferentialControl.hpp" using namespace time_literals; @@ -80,21 +78,17 @@ class RoverDifferential : public ModuleBase, public ModulePar bool init(); - /** - * @brief Computes motor commands for differential drive. - * - * @param forward_speed Linear velocity along the x-axis. - * @param speed_diff Speed difference between left and right wheels. - * @return matrix::Vector2f Motor velocities for the right and left motors. - */ - matrix::Vector2f computeMotorCommands(float forward_speed, const float speed_diff); - protected: void updateParams() override; private: void Run() override; + /** + * @brief Update uORB subscriptions. + */ + void updateSubscriptions(); + // uORB Subscriptions uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; @@ -104,33 +98,22 @@ class RoverDifferential : public ModuleBase, public ModulePar uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; // uORB Publications - uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; - uORB::Publication _rover_differential_status_pub{ORB_ID(rover_differential_status)}; + uORB::Publication _rover_differential_setpoint_pub{ORB_ID(rover_differential_setpoint)}; // Instances RoverDifferentialGuidance _rover_differential_guidance{this}; + RoverDifferentialControl _rover_differential_control{this}; // Variables - float _vehicle_body_yaw_rate{0.f}; + matrix::Quatf _vehicle_attitude_quaternion{}; + float _vehicle_yaw_rate{0.f}; float _vehicle_forward_speed{0.f}; float _vehicle_yaw{0.f}; float _max_yaw_rate{0.f}; int _nav_state{0}; - matrix::Quatf _vehicle_attitude_quaternion{}; - hrt_abstime _timestamp{0}; - PID_t _pid_yaw_rate; // The PID controller for yaw rate - RoverDifferentialGuidance::differential_setpoint _differential_setpoint; - - // Constants - static constexpr float YAW_RATE_ERROR_THRESHOLD = 0.1f; // [rad/s] Error threshold for the closed loop yaw rate control DEFINE_PARAMETERS( (ParamFloat) _param_rd_man_yaw_scale, - (ParamFloat) _param_rd_wheel_track, - (ParamFloat) _param_rd_p_gain_yaw_rate, - (ParamFloat) _param_rd_i_gain_yaw_rate, - (ParamFloat) _param_rd_max_speed, - (ParamFloat) _param_rd_max_yaw_rate, - (ParamInt) _param_r_rev + (ParamFloat) _param_rd_max_yaw_rate ) }; diff --git a/src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt b/src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt new file mode 100644 index 000000000000..58a5239f8cc7 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt @@ -0,0 +1,39 @@ +############################################################################ +# +# 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. +# +############################################################################ + +px4_add_library(RoverDifferentialControl + RoverDifferentialControl.cpp +) + +target_link_libraries(RoverDifferentialControl PUBLIC pid) +target_include_directories(RoverDifferentialControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp new file mode 100644 index 000000000000..c1f96c0ce066 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp @@ -0,0 +1,176 @@ +/**************************************************************************** + * + * 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 "RoverDifferentialControl.hpp" + +#include + +using namespace matrix; +using namespace time_literals; + +RoverDifferentialControl::RoverDifferentialControl(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_differential_status_pub.advertise(); + pid_init(&_pid_yaw_rate, PID_MODE_DERIVATIV_NONE, 0.001f); + pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f); + pid_init(&_pid_yaw, PID_MODE_DERIVATIV_NONE, 0.001f); +} + +void RoverDifferentialControl::updateParams() +{ + ModuleParams::updateParams(); + _max_yaw_rate = _param_rd_max_yaw_rate.get() * M_DEG_TO_RAD_F; + pid_set_parameters(&_pid_yaw_rate, + _param_rd_yaw_rate_p.get(), // Proportional gain + _param_rd_yaw_rate_i.get(), // Integral gain + 0.f, // Derivative gain + 1.f, // Integral limit + 1.f); // Output limit + pid_set_parameters(&_pid_throttle, + _param_rd_p_gain_speed.get(), // Proportional gain + _param_rd_i_gain_speed.get(), // Integral gain + 0.f, // Derivative gain + 1.f, // Integral limit + 1.f); // Output limit + pid_set_parameters(&_pid_yaw, + _param_rd_p_gain_yaw.get(), // Proportional gain + _param_rd_i_gain_yaw.get(), // Integral gain + 0.f, // Derivative gain + _max_yaw_rate, // Integral limit + _max_yaw_rate); // Output limit +} + +void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, const float vehicle_yaw_rate, + const float vehicle_forward_speed) +{ + // Timestamps + hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + + // Update differential setpoint + _rover_differential_setpoint_sub.update(&_rover_differential_setpoint); + + // Closed loop yaw control (Overrides yaw rate setpoint) + if (PX4_ISFINITE(_rover_differential_setpoint.yaw_setpoint)) { + if (fabsf(_rover_differential_setpoint.yaw_setpoint - vehicle_yaw) < FLT_EPSILON) { + _rover_differential_setpoint.yaw_rate_setpoint = 0.f; + pid_reset_integral(&_pid_yaw); + + } else { + const float heading_error = matrix::wrap_pi(_rover_differential_setpoint.yaw_setpoint - vehicle_yaw); + _rover_differential_setpoint.yaw_rate_setpoint = pid_calculate(&_pid_yaw, heading_error, 0, 0, dt); + } + } + + // Yaw rate control + float speed_diff_normalized{0.f}; + + if (PX4_ISFINITE(_rover_differential_setpoint.yaw_rate_setpoint)) { // Closed loop yaw rate control + if (fabsf(_rover_differential_setpoint.yaw_rate_setpoint) < FLT_EPSILON) { + speed_diff_normalized = 0.f; + pid_reset_integral(&_pid_yaw_rate); + + } else { + const float speed_diff = _rover_differential_setpoint.yaw_rate_setpoint * _param_rd_wheel_track.get(); // Feedforward + speed_diff_normalized = math::interpolate(speed_diff, -_param_rd_max_speed.get(), + _param_rd_max_speed.get(), -1.f, 1.f); + speed_diff_normalized = math::constrain(speed_diff_normalized + + pid_calculate(&_pid_yaw_rate, _rover_differential_setpoint.yaw_rate_setpoint, vehicle_yaw_rate, 0, dt), + -1.f, 1.f); // Feedback + } + + } else { // Use normalized setpoint + speed_diff_normalized = PX4_ISFINITE(_rover_differential_setpoint.yaw_rate_setpoint_normalized) ? + math::constrain(_rover_differential_setpoint.yaw_rate_setpoint_normalized, -1.f, 1.f) : 0.f; + } + + // Speed control + float throttle{0.f}; + + if (PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint)) { // Closed loop speed control + if (fabsf(_rover_differential_setpoint.forward_speed_setpoint) < FLT_EPSILON) { + pid_reset_integral(&_pid_throttle); + + } else { + throttle = pid_calculate(&_pid_throttle, _rover_differential_setpoint.forward_speed_setpoint, vehicle_forward_speed, 0, + dt); + + if (_param_rd_max_speed.get() > FLT_EPSILON) { // Feed-forward term + throttle += math::interpolate(_rover_differential_setpoint.forward_speed_setpoint, + 0.f, _param_rd_max_speed.get(), + 0.f, 1.f); + } + } + + } else { // Use normalized setpoint + throttle = PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint_normalized) ? + math::constrain(_rover_differential_setpoint.forward_speed_setpoint_normalized, -1.f, 1.f) : 0.f; + } + + // Publish rover differential status (logging) + rover_differential_status_s rover_differential_status{}; + rover_differential_status.timestamp = _timestamp; + rover_differential_status.actual_speed = vehicle_forward_speed; + rover_differential_status.actual_yaw_deg = M_RAD_TO_DEG_F * vehicle_yaw; + rover_differential_status.desired_yaw_rate_deg_s = M_RAD_TO_DEG_F * _rover_differential_setpoint.yaw_rate_setpoint; + rover_differential_status.actual_yaw_rate_deg_s = M_RAD_TO_DEG_F * vehicle_yaw_rate; + rover_differential_status.pid_yaw_rate_integral = _pid_yaw_rate.integral; + rover_differential_status.pid_throttle_integral = _pid_throttle.integral; + rover_differential_status.pid_yaw_integral = _pid_yaw.integral; + _rover_differential_status_pub.publish(rover_differential_status); + + // Publish to motors + actuator_motors_s actuator_motors{}; + actuator_motors.reversible_flags = _param_r_rev.get(); + computeInverseKinematics(throttle, speed_diff_normalized).copyTo(actuator_motors.control); + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + +} + +matrix::Vector2f RoverDifferentialControl::computeInverseKinematics(float forward_speed_normalized, + const float speed_diff_normalized) +{ + float max_motor_command = fabsf(forward_speed_normalized) + fabsf(speed_diff_normalized); + + if (max_motor_command > 1.0f) { // Prioritize yaw rate if a normalized motor command exceeds limit of 1 + float excess = fabsf(max_motor_command - 1.0f); + forward_speed_normalized -= sign(forward_speed_normalized) * excess; + } + + // Calculate the left and right wheel speeds + return Vector2f(forward_speed_normalized - speed_diff_normalized, + forward_speed_normalized + speed_diff_normalized); +} diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp new file mode 100644 index 000000000000..d3ef7a076fd6 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp @@ -0,0 +1,121 @@ +/**************************************************************************** + * + * 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 + +// PX4 includes +#include + +// uORB includes +#include +#include +#include +#include +#include +#include + + +// Standard libraries +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Class for differential rover guidance. + */ +class RoverDifferentialControl : public ModuleParams +{ +public: + /** + * @brief Constructor for RoverDifferentialControl. + * @param parent The parent ModuleParams object. + */ + RoverDifferentialControl(ModuleParams *parent); + ~RoverDifferentialControl() = default; + + /** + * @brief Compute motor commands based on setpoints + */ + void computeMotorCommands(float vehicle_yaw, float vehicle_yaw_rate, float vehicle_forward_speed); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Compute normalized motor commands based on normalized setpoints. + * + * @param forward_speed_normalized Normalized forward speed [-1, 1]. + * @param speed_diff_normalized Speed difference between left and right wheels [-1, 1]. + * @return matrix::Vector2f Motor velocities for the right and left motors [-1, 1]. + */ + matrix::Vector2f computeInverseKinematics(float forward_speed_normalized, const float speed_diff_normalized); + + // uORB subscriptions + uORB::Subscription _rover_differential_setpoint_sub{ORB_ID(rover_differential_setpoint)}; + + // uORB publications + uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _rover_differential_status_pub{ORB_ID(rover_differential_status)}; + + // Variables + rover_differential_setpoint_s _rover_differential_setpoint{}; + hrt_abstime _timestamp{0}; + float _max_yaw_rate{0.f}; + + // Controllers + PID_t _pid_throttle; // The PID controller for the closed loop speed control + PID_t _pid_yaw; // The PID controller for the closed loop yaw control + PID_t _pid_yaw_rate; // The PID controller for the closed loop yaw rate control + + // Parameters + DEFINE_PARAMETERS( + (ParamFloat) _param_rd_wheel_track, + (ParamFloat) _param_rd_max_speed, + (ParamFloat) _param_rd_max_yaw_rate, + (ParamFloat) _param_rd_yaw_rate_p, + (ParamFloat) _param_rd_yaw_rate_i, + (ParamFloat) _param_rd_p_gain_speed, + (ParamFloat) _param_rd_i_gain_speed, + (ParamFloat) _param_rd_p_gain_yaw, + (ParamFloat) _param_rd_i_gain_yaw, + (ParamInt) _param_r_rev + ) +}; diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt b/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt index 0fd7b68c394e..81f350d48403 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt +++ b/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt @@ -35,5 +35,4 @@ px4_add_library(RoverDifferentialGuidance RoverDifferentialGuidance.cpp ) -target_link_libraries(RoverDifferentialGuidance PUBLIC pid) target_include_directories(RoverDifferentialGuidance PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp index efad52e7b874..848a7f513acf 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -36,108 +36,45 @@ #include using namespace matrix; -using namespace time_literals; RoverDifferentialGuidance::RoverDifferentialGuidance(ModuleParams *parent) : ModuleParams(parent) { updateParams(); + _max_forward_speed = _param_rd_miss_spd_def.get(); _rover_differential_guidance_status_pub.advertise(); - pid_init(&_pid_heading, PID_MODE_DERIVATIV_NONE, 0.001f); - pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f); - } void RoverDifferentialGuidance::updateParams() { ModuleParams::updateParams(); - - _max_yaw_rate = _param_rd_max_yaw_rate.get() * M_DEG_TO_RAD_F; - pid_set_parameters(&_pid_heading, - _param_rd_p_gain_heading.get(), // Proportional gain - _param_rd_i_gain_heading.get(), // Integral gain - 0.f, // Derivative gain - _max_yaw_rate, // Integral limit - _max_yaw_rate); // Output limit - pid_set_parameters(&_pid_throttle, - _param_rd_p_gain_speed.get(), // Proportional gain - _param_rd_i_gain_speed.get(), // Integral gain - 0.f, // Derivative gain - 1.f, // Integral limit - 1.f); // Output limit } -RoverDifferentialGuidance::differential_setpoint RoverDifferentialGuidance::computeGuidance(const float yaw, - const float actual_speed, const int nav_state) +void RoverDifferentialGuidance::computeGuidance(const float vehicle_yaw, const float forward_speed, const int nav_state) { - // Initializations - bool mission_finished{false}; - float desired_speed{0.f}; - float desired_yaw_rate{0.f}; - hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - // uORB subscriber updates - if (_vehicle_global_position_sub.updated()) { - vehicle_global_position_s vehicle_global_position{}; - _vehicle_global_position_sub.copy(&vehicle_global_position); - _curr_pos = Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); - } + updateSubscriptions(); - if (_local_position_sub.updated()) { - vehicle_local_position_s local_position{}; - _local_position_sub.copy(&local_position); + // Catch return to launch + const float distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _curr_wp(0), _curr_wp(1)); - if (!_global_ned_proj_ref.isInitialized() - || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != local_position.ref_timestamp)) { - _global_ned_proj_ref.initReference(local_position.ref_lat, local_position.ref_lon, local_position.ref_timestamp); - } - - _curr_pos_ned = Vector2f(local_position.x, local_position.y); - } - - if (_position_setpoint_triplet_sub.updated()) { - updateWaypoints(); - } - - if (_mission_result_sub.updated()) { - mission_result_s mission_result{}; - _mission_result_sub.copy(&mission_result); - mission_finished = mission_result.finished; - } - - if (_home_position_sub.updated()) { - home_position_s home_position{}; - _home_position_sub.copy(&home_position); - _home_position = Vector2d(home_position.lat, home_position.lon); - } - - const float desired_heading = _pure_pursuit.calcDesiredHeading(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, - math::max(actual_speed, 0.f)); - - const float heading_error = matrix::wrap_pi(desired_heading - yaw); - - const float distance_to_next_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - _curr_wp(0), - _curr_wp(1)); - - if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL - && distance_to_next_wp < _param_nav_acc_rad.get()) { // Return to launch - mission_finished = true; + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + _mission_finished = distance_to_curr_wp < _param_nav_acc_rad.get(); } // State machine - if (!mission_finished && distance_to_next_wp > _param_nav_acc_rad.get()) { + float desired_yaw = _pure_pursuit.calcDesiredHeading(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, + math::max(forward_speed, 0.f)); + const float heading_error = matrix::wrap_pi(desired_yaw - vehicle_yaw); + + if (!_mission_finished && distance_to_curr_wp > _param_nav_acc_rad.get()) { if (_currentState == GuidanceState::STOPPED) { _currentState = GuidanceState::DRIVING; } if (_currentState == GuidanceState::DRIVING && fabsf(heading_error) > _param_rd_trans_drv_trn.get()) { - pid_reset_integral(&_pid_heading); _currentState = GuidanceState::SPOT_TURNING; } else if (_currentState == GuidanceState::SPOT_TURNING && fabsf(heading_error) < _param_rd_trans_trn_drv.get()) { - pid_reset_integral(&_pid_heading); _currentState = GuidanceState::DRIVING; } @@ -146,68 +83,93 @@ RoverDifferentialGuidance::differential_setpoint RoverDifferentialGuidance::comp } // Guidance logic + float desired_forward_speed{0.f}; + switch (_currentState) { case GuidanceState::DRIVING: { - desired_speed = _param_rd_miss_spd_def.get(); - - if (_param_rd_max_jerk.get() > FLT_EPSILON && _param_rd_max_accel.get() > FLT_EPSILON) { - desired_speed = math::trajectory::computeMaxSpeedFromDistance(_param_rd_max_jerk.get(), - _param_rd_max_accel.get(), distance_to_next_wp, 0.0f); - desired_speed = math::constrain(desired_speed, -_param_rd_max_speed.get(), _param_rd_max_speed.get()); + // Calculate desired forward speed + desired_forward_speed = _max_forward_speed; + + if (_waypoint_transition_angle < M_PI_F - _param_rd_trans_drv_trn.get()) { + if (_param_rd_max_jerk.get() > FLT_EPSILON && _param_rd_max_accel.get() > FLT_EPSILON) { + desired_forward_speed = math::trajectory::computeMaxSpeedFromDistance(_param_rd_max_jerk.get(), + _param_rd_max_accel.get(), distance_to_curr_wp, 0.0f); + desired_forward_speed = math::constrain(desired_forward_speed, -_max_forward_speed, _max_forward_speed); + } } - desired_yaw_rate = pid_calculate(&_pid_heading, heading_error, 0.f, 0.f, dt); } break; case GuidanceState::SPOT_TURNING: - if (actual_speed < TURN_MAX_VELOCITY) { // Wait for the rover to stop - desired_yaw_rate = pid_calculate(&_pid_heading, heading_error, 0.f, 0.f, dt); // Turn on the spot + if (forward_speed > TURN_MAX_VELOCITY) { + desired_yaw = vehicle_yaw; // Wait for the rover to stop + } break; case GuidanceState::STOPPED: default: - desired_speed = 0.f; - desired_yaw_rate = 0.f; + desired_yaw = vehicle_yaw; break; } - // Closed loop speed control - float throttle{0.f}; + // Publish differential guidance status (logging) + hrt_abstime timestamp = hrt_absolute_time(); + rover_differential_guidance_status_s rover_differential_guidance_status{}; + rover_differential_guidance_status.timestamp = timestamp; + rover_differential_guidance_status.lookahead_distance = _pure_pursuit.getLookaheadDistance(); + rover_differential_guidance_status.heading_error_deg = M_RAD_TO_DEG_F * heading_error; + rover_differential_guidance_status.state_machine = (uint8_t) _currentState; + _rover_differential_guidance_status_pub.publish(rover_differential_guidance_status); + + // Publish setpoints + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.timestamp = timestamp; + rover_differential_setpoint.forward_speed_setpoint = desired_forward_speed; + rover_differential_setpoint.forward_speed_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_rate_setpoint = NAN; + rover_differential_setpoint.yaw_rate_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_setpoint = desired_yaw; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); +} - if (fabsf(desired_speed) < FLT_EPSILON) { - pid_reset_integral(&_pid_throttle); +void RoverDifferentialGuidance::updateSubscriptions() +{ + if (_vehicle_global_position_sub.updated()) { + vehicle_global_position_s vehicle_global_position{}; + _vehicle_global_position_sub.copy(&vehicle_global_position); + _curr_pos = Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); + } - } else { - throttle = pid_calculate(&_pid_throttle, desired_speed, actual_speed, 0, - dt); + if (_local_position_sub.updated()) { + vehicle_local_position_s local_position{}; + _local_position_sub.copy(&local_position); - if (_param_rd_max_speed.get() > FLT_EPSILON) { // Feed-forward term - throttle += math::interpolate(desired_speed, - 0.f, _param_rd_max_speed.get(), - 0.f, 1.f); + if (!_global_ned_proj_ref.isInitialized() + || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != local_position.ref_timestamp)) { + _global_ned_proj_ref.initReference(local_position.ref_lat, local_position.ref_lon, local_position.ref_timestamp); } + + _curr_pos_ned = Vector2f(local_position.x, local_position.y); } - // Publish differential controller status (logging) - _rover_differential_guidance_status.timestamp = _timestamp; - _rover_differential_guidance_status.desired_speed = desired_speed; - _rover_differential_guidance_status.pid_throttle_integral = _pid_throttle.integral; - _rover_differential_guidance_status.lookahead_distance = _pure_pursuit.getLookaheadDistance(); - _rover_differential_guidance_status.pid_heading_integral = _pid_heading.integral; - _rover_differential_guidance_status.heading_error_deg = M_RAD_TO_DEG_F * heading_error; - _rover_differential_guidance_status.state_machine = (uint8_t) _currentState; - _rover_differential_guidance_status_pub.publish(_rover_differential_guidance_status); - - // Return setpoints - differential_setpoint differential_setpoint_temp; - differential_setpoint_temp.throttle = math::constrain(throttle, 0.f, 1.f); - differential_setpoint_temp.yaw_rate = math::constrain(desired_yaw_rate, -_max_yaw_rate, - _max_yaw_rate); - differential_setpoint_temp.closed_loop_yaw_rate = true; - return differential_setpoint_temp; + if (_position_setpoint_triplet_sub.updated()) { + updateWaypoints(); + } + + if (_mission_result_sub.updated()) { + mission_result_s mission_result{}; + _mission_result_sub.copy(&mission_result); + _mission_finished = mission_result.finished; + } + + if (_home_position_sub.updated()) { + home_position_s home_position{}; + _home_position_sub.copy(&home_position); + _home_position = Vector2d(home_position.lat, home_position.lon); + } } void RoverDifferentialGuidance::updateWaypoints() @@ -243,5 +205,20 @@ void RoverDifferentialGuidance::updateWaypoints() // NED waypoint coordinates _curr_wp_ned = _global_ned_proj_ref.project(_curr_wp(0), _curr_wp(1)); _prev_wp_ned = _global_ned_proj_ref.project(_prev_wp(0), _prev_wp(1)); + _next_wp_ned = _global_ned_proj_ref.project(_next_wp(0), _next_wp(1)); + // Distances + const Vector2f curr_to_next_wp_ned = _next_wp_ned - _curr_wp_ned; + const Vector2f curr_to_prev_wp_ned = _prev_wp_ned - _curr_wp_ned; + float cosin = curr_to_prev_wp_ned.unit_or_zero() * curr_to_next_wp_ned.unit_or_zero(); + cosin = math::constrain(cosin, -1.f, 1.f); // Protect against float precision problem + _waypoint_transition_angle = acosf(cosin); + + // Waypoint cruising speed + if (position_setpoint_triplet.current.cruising_speed > 0.f) { + _max_forward_speed = math::constrain(position_setpoint_triplet.current.cruising_speed, 0.f, _param_rd_max_speed.get()); + + } else { + _max_forward_speed = _param_rd_miss_spd_def.get(); + } } diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp index 29a131f8d8e2..fd3a9485a04e 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -47,9 +47,9 @@ #include #include #include +#include // Standard libraries -#include #include #include #include @@ -80,26 +80,13 @@ class RoverDifferentialGuidance : public ModuleParams RoverDifferentialGuidance(ModuleParams *parent); ~RoverDifferentialGuidance() = default; - struct differential_setpoint { - float throttle{0.f}; - float yaw_rate{0.f}; - bool closed_loop_yaw_rate{false}; - }; - /** - * @brief Compute guidance for the vehicle. - * @param yaw The yaw orientation of the vehicle in radians. - * @param actual_speed The velocity of the vehicle in m/s. - * @param dt The time step in seconds. + * @brief Compute and publish attitude and velocity setpoints based on the mission plan. + * @param vehicle_yaw The yaw of the vehicle [rad]. + * @param forward_speed The forward speed of the vehicle [m/s]. * @param nav_state Navigation state of the rover. */ - RoverDifferentialGuidance::differential_setpoint computeGuidance(float yaw, float actual_speed, - int nav_state); - - /** - * @brief Update global/ned waypoint coordinates - */ - void updateWaypoints(); + void computeGuidance(float vehicle_yaw, float forward_speed, int nav_state); protected: /** @@ -108,6 +95,16 @@ class RoverDifferentialGuidance : public ModuleParams void updateParams() override; private: + /** + * @brief Update uORB subscriptions. + */ + void updateSubscriptions(); + + /** + * @brief Update global/ned waypoint coordinates + */ + void updateWaypoints(); + // uORB subscriptions uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; @@ -116,16 +113,14 @@ class RoverDifferentialGuidance : public ModuleParams uORB::Subscription _home_position_sub{ORB_ID(home_position)}; // uORB publications + uORB::Publication _rover_differential_setpoint_pub{ORB_ID(rover_differential_setpoint)}; uORB::Publication _rover_differential_guidance_status_pub{ORB_ID(rover_differential_guidance_status)}; - rover_differential_guidance_status_s _rover_differential_guidance_status{}; // Variables MapProjection _global_ned_proj_ref{}; // Transform global to ned coordinates. - GuidanceState _currentState{GuidanceState::DRIVING}; // The current state of guidance. + GuidanceState _currentState{GuidanceState::DRIVING}; // The current state of the guidance. PurePursuit _pure_pursuit{this}; // Pure pursuit library - hrt_abstime _timestamp{0}; - float _max_yaw_rate{0.f}; - + bool _mission_finished{false}; // Waypoints Vector2d _curr_pos{}; @@ -135,27 +130,21 @@ class RoverDifferentialGuidance : public ModuleParams Vector2d _curr_wp{}; Vector2f _curr_wp_ned{}; Vector2d _next_wp{}; + Vector2f _next_wp_ned{}; Vector2d _home_position{}; - - // Controllers - PID_t _pid_heading; // The PID controller for the heading - PID_t _pid_throttle; // The PID controller for velocity + float _max_forward_speed{0.f}; // Maximum forward speed for the rover [m/s] + float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] // Constants static constexpr float TURN_MAX_VELOCITY = 0.2f; // Velocity threshhold for starting the spot turn [m/s] // Parameters DEFINE_PARAMETERS( - (ParamFloat) _param_rd_p_gain_heading, - (ParamFloat) _param_rd_i_gain_heading, - (ParamFloat) _param_rd_p_gain_speed, - (ParamFloat) _param_rd_i_gain_speed, (ParamFloat) _param_rd_max_speed, (ParamFloat) _param_nav_acc_rad, (ParamFloat) _param_rd_max_jerk, (ParamFloat) _param_rd_max_accel, (ParamFloat) _param_rd_miss_spd_def, - (ParamFloat) _param_rd_max_yaw_rate, (ParamFloat) _param_rd_trans_trn_drv, (ParamFloat) _param_rd_trans_drv_trn diff --git a/src/modules/rover_differential/module.yaml b/src/modules/rover_differential/module.yaml index be0a76c60e9b..edc3f8e5ba7f 100644 --- a/src/modules/rover_differential/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -23,70 +23,70 @@ parameters: In manual mode the setpoint for the yaw rate received from the rc remote is scaled by this value. type: float - min: 0.01 + min: 0.001 max: 1 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 - RD_HEADING_P: + RD_YAW_P: description: - short: Proportional gain for heading controller + short: Proportional gain for closed loop yaw controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 - RD_HEADING_I: + RD_YAW_I: description: - short: Integral gain for heading controller + short: Integral gain for closed loop yaw controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 - default: 0.1 + decimal: 3 + default: 0 RD_SPEED_P: description: - short: Proportional gain for speed controller + short: Proportional gain for closed loop forward speed controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 RD_SPEED_I: description: - short: Integral gain for ground speed controller + short: Integral gain for closed loop forward speed controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 0 RD_YAW_RATE_P: description: - short: Proportional gain for angular velocity controller + short: Proportional gain for closed loop yaw rate controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 RD_YAW_RATE_I: description: - short: Integral gain for angular velocity controller + short: Integral gain for closed loop yaw rate controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 0 RD_MAX_JERK: @@ -123,11 +123,11 @@ parameters: max: 100 increment: 0.01 decimal: 2 - default: 7 + default: 1 RD_MAX_YAW_RATE: description: - short: Maximum allowed yaw rate for the rover. + short: Maximum allowed yaw rate for the rover long: | This parameter is used to cap desired yaw rates and map controller inputs to desired yaw rates in acro mode. type: float @@ -140,7 +140,7 @@ parameters: RD_MISS_SPD_DEF: description: - short: Default rover speed during a mission + short: Default forward speed for the rover during auto modes type: float unit: m/s min: 0 @@ -151,7 +151,7 @@ parameters: RD_TRANS_TRN_DRV: description: - short: Heading error threshhold to switch from spot turning to driving + short: Yaw error threshhold to switch from spot turning to driving type: float unit: rad min: 0.001 @@ -162,7 +162,12 @@ parameters: RD_TRANS_DRV_TRN: description: - short: Heading error threshhold to switch from driving to spot turning + short: Yaw error threshhold to switch from driving to spot turning + long: | + This threshold is used for the state machine to switch from driving to turning based on the + error between the desired and actual yaw. It is also used as the threshold whether the rover should come + to a smooth stop at the next waypoint. This slow down effect is active if the angle between the + line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN. type: float unit: rad min: 0.001 From 5b0014cb06eabc0d735d0509487c6e71ea76614a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 29 Aug 2024 11:51:27 -0400 Subject: [PATCH 19/31] ekf2: remove legacy accel z bias checks (#23341) Co-authored-by: Mathieu Bresciani --- .../scripts/itcm_functions_includes.ld | 1 - msg/EstimatorStatusFlags.msg | 1 - src/modules/ekf2/EKF/common.h | 2 +- src/modules/ekf2/EKF/ekf.cpp | 2 - src/modules/ekf2/EKF/ekf.h | 3 - src/modules/ekf2/EKF/height_control.cpp | 101 ------------------ src/modules/ekf2/EKF2.cpp | 2 - 7 files changed, 1 insertion(+), 111 deletions(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld index 9b169ae36005..0a4e0faa6ae7 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld @@ -377,7 +377,6 @@ *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) *(.text.imxrt_epsubmit) *(.text._ZN15PositionControl6updateEf) -*(.text._ZN3Ekf29checkVerticalAccelerationBiasERKN9estimator9imuSampleE) *(.text._ZN23MavlinkStreamScaledIMU24sendEv) *(.text._ZN5PX4IO10io_reg_getEhhPtj) *(.text.imxrt_dma_send) diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 79b900f6a8b0..6b17842c2650 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -59,7 +59,6 @@ bool fs_bad_airspeed # 5 - true if fusion of the airspeed has encounte bool fs_bad_sideslip # 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error bool fs_bad_optflow_x # 7 - true if fusion of the optical flow X axis has encountered a numerical error bool fs_bad_optflow_y # 8 - true if fusion of the optical flow Y axis has encountered a numerical error -bool fs_bad_acc_bias # 9 - true if bad delta velocity bias estimates have been detected bool fs_bad_acc_vertical # 10 - true if bad vertical accelerometer data has been detected bool fs_bad_acc_clipping # 11 - true if delta velocity data contains clipping (asymmetric railing) diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 13c2767f754b..6eda8b9cc71f 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -513,7 +513,7 @@ bool bad_sideslip : 1; ///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error bool bad_optflow_X : 1; ///< 7 - true if fusion of the optical flow X axis has encountered a numerical error bool bad_optflow_Y : 1; ///< 8 - true if fusion of the optical flow Y axis has encountered a numerical error - bool bad_acc_bias : 1; ///< 9 - true if bad delta velocity bias estimates have been detected + bool __UNUSED : 1; ///< 9 - bool bad_acc_vertical : 1; ///< 10 - true if bad vertical accelerometer data has been detected bool bad_acc_clipping : 1; ///< 11 - true if delta velocity data contains clipping (asymmetric railing) } flags; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 24734dcfb370..c8448daa9b3e 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -114,8 +114,6 @@ void Ekf::reset() _last_known_pos.setZero(); - _time_acc_bias_check = 0; - #if defined(CONFIG_EKF2_BAROMETER) _baro_counter = 0; #endif // CONFIG_EKF2_BAROMETER diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 5be5cee3bbad..a7d59b47ef5d 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -612,8 +612,6 @@ class Ekf final : public EstimatorInterface Vector3f _last_known_pos{}; ///< last known local position vector (m) - uint64_t _time_acc_bias_check{0}; ///< last time the accel bias check passed (uSec) - Vector3f _earth_rate_NED{}; ///< earth rotation vector (NED) in rad/s Dcmf _R_to_earth{}; ///< transformation matrix from body frame to earth frame from last EKF prediction @@ -1094,7 +1092,6 @@ class Ekf final : public EstimatorInterface void stopAuxVelFusion(); #endif // CONFIG_EKF2_AUXVEL - void checkVerticalAccelerationBias(const imuSample &imu_delayed); void checkVerticalAccelerationHealth(const imuSample &imu_delayed); Likelihood estimateInertialNavFallingLikelihood() const; diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index 4db232ca051f..147e198921cf 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -39,7 +39,6 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed) { - checkVerticalAccelerationBias(imu_delayed); checkVerticalAccelerationHealth(imu_delayed); #if defined(CONFIG_EKF2_BAROMETER) @@ -120,106 +119,6 @@ void Ekf::checkHeightSensorRefFallback() } } -void Ekf::checkVerticalAccelerationBias(const imuSample &imu_delayed) -{ - // Run additional checks to see if the delta velocity bias has hit limits in a direction that is clearly wrong - // calculate accel bias term aligned with the gravity vector - const float dVel_bias_lim = 0.9f * _params.acc_bias_lim * _dt_ekf_avg; - const Vector3f delta_vel_bias = _state.accel_bias * _dt_ekf_avg; - const float down_dvel_bias = delta_vel_bias.dot(Vector3f(_R_to_earth.row(2))); - - // check that the vertical component of accel bias is consistent with both the vertical position and velocity innovation - bool bad_acc_bias = false; - - if (fabsf(down_dvel_bias) > dVel_bias_lim) { - - bool bad_vz = false; - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - - if (_control_status.flags.ev_hgt) { - if (down_dvel_bias * _aid_src_ev_vel.innovation[2] < 0.f) { - bad_vz = true; - } - } - -#endif // CONFIG_EKF2_EXTERNAL_VISION - -#if defined(CONFIG_EKF2_GNSS) - - if (_control_status.flags.gps) { - if (down_dvel_bias * _aid_src_gnss_vel.innovation[2] < 0.f) { - bad_vz = true; - } - } - -#endif // CONFIG_EKF2_GNSS - - if (bad_vz) { -#if defined(CONFIG_EKF2_BAROMETER) - - if (_control_status.flags.baro_hgt) { - if (down_dvel_bias * _aid_src_baro_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_BAROMETER - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - - if (_control_status.flags.ev_hgt) { - if (down_dvel_bias * _aid_src_ev_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_EXTERNAL_VISION - -#if defined(CONFIG_EKF2_GNSS) - - if (_control_status.flags.gps_hgt) { - if (down_dvel_bias * _aid_src_gnss_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_GNSS - -#if defined(CONFIG_EKF2_RANGE_FINDER) - - if (_control_status.flags.rng_hgt) { - if (down_dvel_bias * _aid_src_rng_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_RANGE_FINDER - } - } - - // record the pass/fail - if (!bad_acc_bias) { - _fault_status.flags.bad_acc_bias = false; - _time_acc_bias_check = _time_delayed_us; - - } else { - _fault_status.flags.bad_acc_bias = true; - } - - // if we have failed for 7 seconds continuously, reset the accel bias covariances to fix bad conditioning of - // the covariance matrix but preserve the variances (diagonals) to allow bias learning to continue - if (_fault_status.flags.bad_acc_bias && isTimedOut(_time_acc_bias_check, (uint64_t)7e6)) { - - resetAccelBiasCov(); - - _time_acc_bias_check = imu_delayed.time_us; - - _fault_status.flags.bad_acc_bias = false; - ECL_WARN("invalid accel bias - covariance reset"); - } -} - void Ekf::checkVerticalAccelerationHealth(const imuSample &imu_delayed) { // Check for IMU accelerometer vibration induced clipping as evidenced by the vertical diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 7769543d2bbd..97ff93bf2a92 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1937,7 +1937,6 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.fs_bad_sideslip = _ekf.fault_status_flags().bad_sideslip; status_flags.fs_bad_optflow_x = _ekf.fault_status_flags().bad_optflow_X; status_flags.fs_bad_optflow_y = _ekf.fault_status_flags().bad_optflow_Y; - status_flags.fs_bad_acc_bias = _ekf.fault_status_flags().bad_acc_bias; status_flags.fs_bad_acc_vertical = _ekf.fault_status_flags().bad_acc_vertical; status_flags.fs_bad_acc_clipping = _ekf.fault_status_flags().bad_acc_clipping; @@ -2666,7 +2665,6 @@ void EKF2::UpdateAccelCalibration(const hrt_abstime ×tamp) const bool bias_valid = (_param_ekf2_imu_ctrl.get() & static_cast(ImuCtrl::AccelBias)) && _ekf.control_status_flags().tilt_align && (_ekf.fault_status().value == 0) - && !_ekf.fault_status_flags().bad_acc_bias && !_ekf.fault_status_flags().bad_acc_clipping && !_ekf.fault_status_flags().bad_acc_vertical; From 787fe9590d83e2ff4e76d9e3b331edbd3bf9e7d6 Mon Sep 17 00:00:00 2001 From: Benjamin Perseghetti Date: Thu, 29 Aug 2024 14:42:56 -0400 Subject: [PATCH 20/31] Fix typo where 22.04 still says Gz (Garden) (#23632) Signed-off-by: Benjamin Perseghetti --- Tools/setup/ubuntu.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index 346e071cdcc1..48e23709fb84 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -225,7 +225,7 @@ if [[ $INSTALL_SIM == "true" ]]; then # Gazebo / Gazebo classic installation if [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then - echo "Gazebo (Garden) will be installed" + echo "Gazebo (Harmonic) will be installed" echo "Earlier versions will be removed" # Add Gazebo binary repository sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg From 7dcea6b2e498835ba6c656eac7370ba554bec9da Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Fri, 30 Aug 2024 17:25:56 +0200 Subject: [PATCH 21/31] EKF2: range measurement rejection in rain/fog (#23579) --- .../range_finder/range_height_control.cpp | 1 + .../range_finder/sensor_range_finder.cpp | 21 +++++- .../range_finder/sensor_range_finder.hpp | 12 ++++ src/modules/ekf2/EKF/common.h | 1 + src/modules/ekf2/EKF/ekf.cpp | 1 + src/modules/ekf2/EKF2.cpp | 1 + src/modules/ekf2/EKF2.hpp | 1 + src/modules/ekf2/params_range_finder.yaml | 13 ++++ .../ekf2/test/test_SensorRangeFinder.cpp | 64 ++++++++++++++++--- 9 files changed, 106 insertions(+), 9 deletions(-) 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 0aafe8a1b00d..678b6f282ca1 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 @@ -54,6 +54,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) _range_sensor.setPitchOffset(_params.rng_sens_pitch); _range_sensor.setCosMaxTilt(_params.range_cos_max_tilt); _range_sensor.setQualityHysteresis(_params.range_valid_quality_s); + _range_sensor.setMaxFogDistance(_params.rng_fog); _range_sensor.runChecks(imu_sample.time_us, _R_to_earth); diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp index 359d10ca5242..c0ae2a71ebf6 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp @@ -84,8 +84,9 @@ void SensorRangeFinder::updateValidity(uint64_t current_time_us) if (isTiltOk() && isDataInRange()) { updateStuckCheck(); + updateFogCheck(getDistBottom(), _sample.time_us); - if (!_is_stuck) { + if (!_is_stuck && !_is_blocked) { _is_sample_valid = true; _time_last_valid_us = _sample.time_us; } @@ -146,5 +147,23 @@ void SensorRangeFinder::updateStuckCheck() } } +void SensorRangeFinder::updateFogCheck(const float dist_bottom, const uint64_t time_us) +{ + if (_max_fog_dist > 0.f && time_us - _time_last_valid_us < 1e6) { + + const float median_dist = _median_dist.apply(dist_bottom); + const float factor = 2.f; // magic hardcoded factor + + if (!_is_blocked && median_dist < _max_fog_dist && _prev_median_dist - median_dist > factor * _max_fog_dist) { + _is_blocked = true; + + } else if (_is_blocked && median_dist > factor * _max_fog_dist) { + _is_blocked = false; + } + + _prev_median_dist = median_dist; + } +} + } // namespace sensor } // namespace estimator diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp index f3c59be54135..fd53407fa871 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp @@ -44,6 +44,7 @@ #include "Sensor.hpp" #include +#include namespace estimator { @@ -99,6 +100,8 @@ class SensorRangeFinder : public Sensor _rng_valid_max_val = max_distance; } + void setMaxFogDistance(float max_fog_dist) { _max_fog_dist = max_fog_dist; } + void setQualityHysteresis(float valid_quality_threshold_s) { _quality_hyst_us = uint64_t(valid_quality_threshold_s * 1e6f); @@ -129,6 +132,7 @@ class SensorRangeFinder : public Sensor bool isTiltOk() const { return _cos_tilt_rng_to_earth > _range_cos_max_tilt; } bool isDataInRange() const; void updateStuckCheck(); + void updateFogCheck(const float dist_bottom, const uint64_t time_us); rangeSample _sample{}; @@ -172,6 +176,14 @@ class SensorRangeFinder : public Sensor */ uint64_t _time_bad_quality_us{}; ///< timestamp at which range finder signal quality was 0 (used for hysteresis) uint64_t _quality_hyst_us{}; ///< minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (us) + + /* + * Fog check + */ + bool _is_blocked{false}; + float _max_fog_dist{0.f}; //< maximum distance at which the range finder could detect fog (m) + math::MedianFilter _median_dist{}; + float _prev_median_dist{0.f}; }; } // namespace sensor diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 6eda8b9cc71f..cc1d48cf164c 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -421,6 +421,7 @@ struct parameters { float range_valid_quality_s{1.0f}; ///< minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s) float range_cos_max_tilt{0.7071f}; ///< cosine of the maximum tilt angle from the vertical that permits use of range finder and flow data float range_kin_consistency_gate{1.0f}; ///< gate size used by the range finder kinematic consistency check + float rng_fog{0.f}; ///< max distance which a blocked range sensor measures (fog, dirt) [m] Vector3f rng_pos_body{}; ///< xyz position of range sensor in body frame (m) #endif // CONFIG_EKF2_RANGE_FINDER diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index c8448daa9b3e..910eb54dd6c1 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -81,6 +81,7 @@ void Ekf::reset() _range_sensor.setPitchOffset(_params.rng_sens_pitch); _range_sensor.setCosMaxTilt(_params.range_cos_max_tilt); _range_sensor.setQualityHysteresis(_params.range_valid_quality_s); + _range_sensor.setMaxFogDistance(_params.rng_fog); #endif // CONFIG_EKF2_RANGE_FINDER _control_status.value = 0; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 97ff93bf2a92..38e5660e4ff4 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -162,6 +162,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): _param_ekf2_rng_a_igate(_params->range_aid_innov_gate), _param_ekf2_rng_qlty_t(_params->range_valid_quality_s), _param_ekf2_rng_k_gate(_params->range_kin_consistency_gate), + _param_ekf2_rng_fog(_params->rng_fog), _param_ekf2_rng_pos_x(_params->rng_pos_body(0)), _param_ekf2_rng_pos_y(_params->rng_pos_body(1)), _param_ekf2_rng_pos_z(_params->rng_pos_body(2)), diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 867cf9ae5758..489e0bbd5ae0 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -623,6 +623,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem (ParamExtFloat) _param_ekf2_rng_a_igate, (ParamExtFloat) _param_ekf2_rng_qlty_t, (ParamExtFloat) _param_ekf2_rng_k_gate, + (ParamExtFloat) _param_ekf2_rng_fog, (ParamExtFloat) _param_ekf2_rng_pos_x, (ParamExtFloat) _param_ekf2_rng_pos_y, (ParamExtFloat) _param_ekf2_rng_pos_z, diff --git a/src/modules/ekf2/params_range_finder.yaml b/src/modules/ekf2/params_range_finder.yaml index 5baa4fb26775..78c30bbcca85 100644 --- a/src/modules/ekf2/params_range_finder.yaml +++ b/src/modules/ekf2/params_range_finder.yaml @@ -150,3 +150,16 @@ parameters: default: 0.0 unit: m decimal: 3 + EKF2_RNG_FOG: + description: + short: Maximum distance at which the range finder could detect fog (m) + long: Limit for fog detection. If the range finder measures a distance greater + than this value, the measurement is considered to not be blocked by fog or rain. + If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the + measurement may gets rejected. 0 - disabled + type: float + default: 1.0 + min: 0.0 + max: 20.0 + unit: m + decimal: 1 diff --git a/src/modules/ekf2/test/test_SensorRangeFinder.cpp b/src/modules/ekf2/test/test_SensorRangeFinder.cpp index fc515a875768..c2e9d1c667e0 100644 --- a/src/modules/ekf2/test/test_SensorRangeFinder.cpp +++ b/src/modules/ekf2/test/test_SensorRangeFinder.cpp @@ -51,6 +51,7 @@ class SensorRangeFinderTest : public ::testing::Test _range_finder.setPitchOffset(0.f); _range_finder.setCosMaxTilt(0.707f); _range_finder.setLimits(_min_range, _max_range); + _range_finder.setMaxFogDistance(2.f); } // Use this method to clean up any memory, network etc. after each test @@ -60,20 +61,21 @@ class SensorRangeFinderTest : public ::testing::Test protected: SensorRangeFinder _range_finder{}; - const rangeSample _good_sample{(uint64_t)2e6, 1.f, 100}; // {time_us, range, quality} + const rangeSample _good_sample{(uint64_t)2e6, 5.f, 100}; // {time_us, range, quality} const float _min_range{0.5f}; const float _max_range{10.f}; - void updateSensorAtRate(uint64_t duration_us, uint64_t dt_update_us, uint64_t dt_sensor_us); + void updateSensorAtRate(rangeSample sample, uint64_t duration_us, uint64_t dt_update_us, uint64_t dt_sensor_us); void testTilt(const Eulerf &euler, bool should_pass); }; -void SensorRangeFinderTest::updateSensorAtRate(uint64_t duration_us, uint64_t dt_update_us, uint64_t dt_sensor_us) +void SensorRangeFinderTest::updateSensorAtRate(rangeSample sample, uint64_t duration_us, uint64_t dt_update_us, + uint64_t dt_sensor_us) { const Dcmf attitude{Eulerf(0.f, 0.f, 0.f)}; - rangeSample new_sample = _good_sample; - uint64_t t_now_us = _good_sample.time_us; + rangeSample new_sample = sample; + uint64_t t_now_us = sample.time_us; for (int i = 0; i < int(duration_us / dt_update_us); i++) { t_now_us += dt_update_us; @@ -307,7 +309,7 @@ TEST_F(SensorRangeFinderTest, continuity) const uint64_t dt_update_us = 10e3; uint64_t dt_sensor_us = 4e6; uint64_t duration_us = 8e6; - updateSensorAtRate(duration_us, dt_update_us, dt_sensor_us); + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); // THEN: the data should be marked as unhealthy // Note that it also fails the out-of-date test here @@ -317,14 +319,14 @@ TEST_F(SensorRangeFinderTest, continuity) // AND WHEN: the data rate is acceptable dt_sensor_us = 3e5; duration_us = 5e5; - updateSensorAtRate(duration_us, dt_update_us, dt_sensor_us); + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); // THEN: it should still fail until the filter converge // to the new datarate EXPECT_FALSE(_range_finder.isDataHealthy()); EXPECT_FALSE(_range_finder.isHealthy()); - updateSensorAtRate(duration_us, dt_update_us, dt_sensor_us); + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); EXPECT_TRUE(_range_finder.isDataHealthy()); EXPECT_TRUE(_range_finder.isHealthy()); } @@ -345,3 +347,49 @@ TEST_F(SensorRangeFinderTest, distBottom) _range_finder.runChecks(sample.time_us, attitude20); EXPECT_FLOAT_EQ(_range_finder.getDistBottom(), sample.rng * cosf(-0.35)); } + +TEST_F(SensorRangeFinderTest, blockedByFog) +{ + // WHEN: sensor is not blocked by fog + const Dcmf attitude{Eulerf(0.f, 0.f, 0.f)}; + const uint64_t dt_update_us = 10e3; + uint64_t dt_sensor_us = 3e5; + uint64_t duration_us = 5e5; + + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); + // THEN: the data should be marked as healthy + EXPECT_TRUE(_range_finder.isDataHealthy()); + EXPECT_TRUE(_range_finder.isHealthy()); + + + // WHEN: sensor is then blocked by fog + // range jumps to value below 2m + uint64_t t_now_us = _range_finder.getSampleAddress()->time_us; + rangeSample sample{t_now_us, 1.f, 100}; + updateSensorAtRate(sample, duration_us, dt_update_us, dt_sensor_us); + + // THEN: the data should be marked as unhealthy + EXPECT_FALSE(_range_finder.isDataHealthy()); + EXPECT_FALSE(_range_finder.isHealthy()); + + // WHEN: the sensor is not blocked by fog anymore + sample.rng = 5.f; + updateSensorAtRate(sample, duration_us, dt_update_us, dt_sensor_us); + + // THEN: the data should be marked as healthy again + EXPECT_TRUE(_range_finder.isDataHealthy()); + EXPECT_TRUE(_range_finder.isHealthy()); + + // WHEN: the sensor is is not jumping to a value below 2m + while (sample.rng > _min_range) { + sample.time_us += dt_update_us; + _range_finder.setSample(sample); + _range_finder.runChecks(sample.time_us, attitude); + sample.rng -= 0.5f; + } + + // THEN: the data should still be marked as healthy + EXPECT_TRUE(_range_finder.isDataHealthy()); + EXPECT_TRUE(_range_finder.isHealthy()); + +} From 4c63e9e4f992824ba05b229bf2506cc7178eda1a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 May 2024 17:12:26 +1200 Subject: [PATCH 22/31] libuavcan: update DroneCAN submodule Signed-off-by: Julian Oes --- src/drivers/uavcan/libuavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/uavcan/libuavcan b/src/drivers/uavcan/libuavcan index 9a0fd624c448..dce2d4e7d8f4 160000 --- a/src/drivers/uavcan/libuavcan +++ b/src/drivers/uavcan/libuavcan @@ -1 +1 @@ -Subproject commit 9a0fd624c448cad5633720676233f74846387a9f +Subproject commit dce2d4e7d8f41348e571481cd2e4788ac8af900d From 87a63e75be8d6c00a6787420d7e4a34df239203d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 9 May 2024 14:30:55 +1200 Subject: [PATCH 23/31] mavlink: extract OpenDroneID function to lib This extracts the function mapping from MAV_TYPE to MAV_ODID_UA_TYPE to the library, so that it can be re-used later by the remote ID implementation over DroneCAN. Signed-off-by: Julian Oes --- src/lib/CMakeLists.txt | 1 + src/lib/open_drone_id/CMakeLists.txt | 41 +++ .../open_drone_id_translations.cpp | 255 ++++++++++++++++++ .../open_drone_id_translations.hpp | 52 ++++ src/modules/mavlink/CMakeLists.txt | 1 + .../streams/OPEN_DRONE_ID_BASIC_ID.hpp | 95 +------ .../streams/OPEN_DRONE_ID_LOCATION.hpp | 64 +---- 7 files changed, 358 insertions(+), 151 deletions(-) create mode 100644 src/lib/open_drone_id/CMakeLists.txt create mode 100644 src/lib/open_drone_id/open_drone_id_translations.cpp create mode 100644 src/lib/open_drone_id/open_drone_id_translations.hpp diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 7a7b5973fd4a..942c2dcad853 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -60,6 +60,7 @@ add_subdirectory(mathlib EXCLUDE_FROM_ALL) add_subdirectory(mixer_module EXCLUDE_FROM_ALL) add_subdirectory(motion_planning EXCLUDE_FROM_ALL) add_subdirectory(npfg EXCLUDE_FROM_ALL) +add_subdirectory(open_drone_id EXCLUDE_FROM_ALL) add_subdirectory(perf EXCLUDE_FROM_ALL) add_subdirectory(fw_performance_model EXCLUDE_FROM_ALL) add_subdirectory(pid EXCLUDE_FROM_ALL) diff --git a/src/lib/open_drone_id/CMakeLists.txt b/src/lib/open_drone_id/CMakeLists.txt new file mode 100644 index 000000000000..2090d159250e --- /dev/null +++ b/src/lib/open_drone_id/CMakeLists.txt @@ -0,0 +1,41 @@ +############################################################################ +# +# 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. +# +############################################################################ + +px4_add_library(open_drone_id + open_drone_id_translations.cpp + open_drone_id_translations.hpp +) + +add_dependencies(open_drone_id mavlink_c_generate) + +target_compile_options(open_drone_id PRIVATE -Wno-cast-align -Wno-address-of-packed-member) diff --git a/src/lib/open_drone_id/open_drone_id_translations.cpp b/src/lib/open_drone_id/open_drone_id_translations.cpp new file mode 100644 index 000000000000..854e7623043d --- /dev/null +++ b/src/lib/open_drone_id/open_drone_id_translations.cpp @@ -0,0 +1,255 @@ +/**************************************************************************** + * + * 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 "open_drone_id_translations.hpp" +#include +#include + +using namespace time_literals; + + +namespace open_drone_id_translations +{ + +MAV_ODID_UA_TYPE odidTypeForMavType(uint8_t system_type) +{ + switch (system_type) { + case MAV_TYPE_GENERIC: return MAV_ODID_UA_TYPE_OTHER; + + case MAV_TYPE_FIXED_WING: return MAV_ODID_UA_TYPE_AEROPLANE; + + case MAV_TYPE_QUADROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_COAXIAL: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_HELICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_ANTENNA_TRACKER: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_GCS: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_AIRSHIP: return MAV_ODID_UA_TYPE_AIRSHIP; + + case MAV_TYPE_FREE_BALLOON: return MAV_ODID_UA_TYPE_FREE_BALLOON; + + case MAV_TYPE_ROCKET: return MAV_ODID_UA_TYPE_ROCKET; + + case MAV_TYPE_GROUND_ROVER: return MAV_ODID_UA_TYPE_GROUND_OBSTACLE; + + case MAV_TYPE_SURFACE_BOAT: return MAV_ODID_UA_TYPE_OTHER; + + case MAV_TYPE_SUBMARINE: return MAV_ODID_UA_TYPE_OTHER; + + case MAV_TYPE_HEXAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_OCTOROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_TRICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_FLAPPING_WING: return MAV_ODID_UA_TYPE_ORNITHOPTER; + + case MAV_TYPE_KITE: return MAV_ODID_UA_TYPE_KITE; + + case MAV_TYPE_ONBOARD_CONTROLLER: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TILTROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_FIXEDROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TAILSITTER: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TILTWING: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_RESERVED5: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_GIMBAL: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_ADSB: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_PARAFOIL: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; + + case MAV_TYPE_DODECAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_CAMERA: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_CHARGING_STATION: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_FLARM: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_SERVO: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_ODID: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_DECAROTOR: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_BATTERY: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_PARACHUTE: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; + + case MAV_TYPE_LOG: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_OSD: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_IMU: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_GPS: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_WINCH: return MAV_ODID_UA_TYPE_NONE; + + default: return MAV_ODID_UA_TYPE_OTHER; + } +} + +MAV_ODID_SPEED_ACC odidSpeedAccForVariance(float s_variance_m_s) +{ + // TODO: should this be stddev, so square root of variance? + // speed_accuracy + if (s_variance_m_s < 0.3f) { + return MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND; + + } else if (s_variance_m_s < 1.f) { + return MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND; + + } else if (s_variance_m_s < 3.f) { + return MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND; + + } else if (s_variance_m_s < 10.f) { + return MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND; + + } else { + return MAV_ODID_SPEED_ACC_UNKNOWN; + } +} + +MAV_ODID_HOR_ACC odidHorAccForEph(float eph) +{ + if (eph < 1.f) { + return MAV_ODID_HOR_ACC_1_METER; + + } else if (eph < 3.f) { + return MAV_ODID_HOR_ACC_3_METER; + + } else if (eph < 10.f) { + return MAV_ODID_HOR_ACC_10_METER; + + } else if (eph < 30.f) { + return MAV_ODID_HOR_ACC_30_METER; + + } else { + return MAV_ODID_HOR_ACC_UNKNOWN; + } +} + +MAV_ODID_VER_ACC odidVerAccForEpv(float epv) +{ + if (epv < 1.f) { + return MAV_ODID_VER_ACC_1_METER; + + } else if (epv < 3.f) { + return MAV_ODID_VER_ACC_3_METER; + + } else if (epv < 10.f) { + return MAV_ODID_VER_ACC_10_METER; + + } else if (epv < 25.f) { + return MAV_ODID_VER_ACC_25_METER; + + } else if (epv < 45.f) { + return MAV_ODID_VER_ACC_45_METER; + + } else if (epv < 150.f) { + return MAV_ODID_VER_ACC_150_METER; + + } else { + return MAV_ODID_VER_ACC_UNKNOWN; + } +} + + +MAV_ODID_TIME_ACC odidTimeForElapsed(uint64_t elapsed) +{ + if (elapsed < 100_ms) { + return MAV_ODID_TIME_ACC_0_1_SECOND; + + } else if (elapsed < 200_ms) { + return MAV_ODID_TIME_ACC_0_2_SECOND; + + } else if (elapsed < 300_ms) { + return MAV_ODID_TIME_ACC_0_3_SECOND; + + } else if (elapsed < 400_ms) { + return MAV_ODID_TIME_ACC_0_4_SECOND; + + } else if (elapsed < 500_ms) { + return MAV_ODID_TIME_ACC_0_5_SECOND; + + } else if (elapsed < 600_ms) { + return MAV_ODID_TIME_ACC_0_6_SECOND; + + } else if (elapsed < 700_ms) { + return MAV_ODID_TIME_ACC_0_7_SECOND; + + } else if (elapsed < 800_ms) { + return MAV_ODID_TIME_ACC_0_8_SECOND; + + } else if (elapsed < 900_ms) { + return MAV_ODID_TIME_ACC_0_9_SECOND; + + } else if (elapsed < 1000_ms) { + return MAV_ODID_TIME_ACC_1_0_SECOND; + + } else if (elapsed < 1100_ms) { + return MAV_ODID_TIME_ACC_1_1_SECOND; + + } else if (elapsed < 1200_ms) { + return MAV_ODID_TIME_ACC_1_2_SECOND; + + } else if (elapsed < 1300_ms) { + return MAV_ODID_TIME_ACC_1_3_SECOND; + + } else if (elapsed < 1400_ms) { + return MAV_ODID_TIME_ACC_1_4_SECOND; + + } else if (elapsed < 1500_ms) { + return MAV_ODID_TIME_ACC_1_5_SECOND; + + } else { + return MAV_ODID_TIME_ACC_UNKNOWN; + } +} + +} // open_drone_id_translations diff --git a/src/lib/open_drone_id/open_drone_id_translations.hpp b/src/lib/open_drone_id/open_drone_id_translations.hpp new file mode 100644 index 000000000000..4632ed1e14e6 --- /dev/null +++ b/src/lib/open_drone_id/open_drone_id_translations.hpp @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * 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 +#include + +namespace open_drone_id_translations +{ + +MAV_ODID_UA_TYPE odidTypeForMavType(uint8_t system_type); + +MAV_ODID_SPEED_ACC odidSpeedAccForVariance(float s_variance_m_s); + +MAV_ODID_HOR_ACC odidHorAccForEph(float eph); + +MAV_ODID_VER_ACC odidVerAccForEpv(float epv); + +MAV_ODID_TIME_ACC odidTimeForElapsed(uint64_t elapsed); + +} // open_drone_id_translations diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index f42dd6fa9b7b..4a29a6eb0b34 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -135,6 +135,7 @@ px4_add_module( sensor_calibration geo mavlink_c + open_drone_id timesync tunes variable_length_ringbuffer diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp index d7869dcbb6c9..dcc77c660a53 100644 --- a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp @@ -35,6 +35,7 @@ #define OPEN_DRONE_ID_BASIC_ID_HPP #include +#include class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream { @@ -57,98 +58,6 @@ class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; - MAV_ODID_UA_TYPE odidTypeForMavType(uint8_t system_type) - { - switch (system_type) { - case MAV_TYPE_GENERIC: return MAV_ODID_UA_TYPE_OTHER; - - case MAV_TYPE_FIXED_WING: return MAV_ODID_UA_TYPE_AEROPLANE; - - case MAV_TYPE_QUADROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_COAXIAL: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_HELICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_ANTENNA_TRACKER: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_GCS: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_AIRSHIP: return MAV_ODID_UA_TYPE_AIRSHIP; - - case MAV_TYPE_FREE_BALLOON: return MAV_ODID_UA_TYPE_FREE_BALLOON; - - case MAV_TYPE_ROCKET: return MAV_ODID_UA_TYPE_ROCKET; - - case MAV_TYPE_GROUND_ROVER: return MAV_ODID_UA_TYPE_GROUND_OBSTACLE; - - case MAV_TYPE_SURFACE_BOAT: return MAV_ODID_UA_TYPE_OTHER; - - case MAV_TYPE_SUBMARINE: return MAV_ODID_UA_TYPE_OTHER; - - case MAV_TYPE_HEXAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_OCTOROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_TRICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_FLAPPING_WING: return MAV_ODID_UA_TYPE_ORNITHOPTER; - - case MAV_TYPE_KITE: return MAV_ODID_UA_TYPE_KITE; - - case MAV_TYPE_ONBOARD_CONTROLLER: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TILTROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_FIXEDROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TAILSITTER: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TILTWING: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_RESERVED5: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_GIMBAL: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_ADSB: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_PARAFOIL: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; - - case MAV_TYPE_DODECAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_CAMERA: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_CHARGING_STATION: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_FLARM: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_SERVO: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_ODID: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_DECAROTOR: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_BATTERY: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_PARACHUTE: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; - - case MAV_TYPE_LOG: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_OSD: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_IMU: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_GPS: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_WINCH: return MAV_ODID_UA_TYPE_NONE; - - default: return MAV_ODID_UA_TYPE_OTHER; - } - } bool send() override @@ -167,7 +76,7 @@ class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream msg.id_type = MAV_ODID_ID_TYPE_SERIAL_NUMBER; // ua_type: MAV_ODID_UA_TYPE - msg.ua_type = odidTypeForMavType(vehicle_status.system_type); + msg.ua_type = open_drone_id_translations::odidTypeForMavType(vehicle_status.system_type); // uas_id: UAS (Unmanned Aircraft System) ID following the format specified by id_type // TODO: MAV_ODID_ID_TYPE_SERIAL_NUMBER needs to be ANSI/CTA-2063 format diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp index 3a519c5e909a..1eba926a3531 100644 --- a/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp @@ -144,22 +144,7 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream const int speed_vertical_cm_s = roundf(-vel_ned(2) * 100.f); msg.speed_vertical = math::constrain(speed_vertical_cm_s, -6200, 6200); - // speed_accuracy - if (vehicle_gps_position.s_variance_m_s < 0.3f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND; - - } else if (vehicle_gps_position.s_variance_m_s < 1.f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND; - - } else if (vehicle_gps_position.s_variance_m_s < 3.f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND; - - } else if (vehicle_gps_position.s_variance_m_s < 10.f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND; - - } else { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_UNKNOWN; - } + msg.speed_accuracy = open_drone_id_translations::odidSpeedAccForVariance(vehicle_gps_position.s_variance_m_s); updated = true; } @@ -173,45 +158,9 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream msg.altitude_geodetic = static_cast(round(vehicle_gps_position.altitude_msl_m)); // [m] } - // horizontal_accuracy - if (vehicle_gps_position.eph < 1.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_1_METER; - - } else if (vehicle_gps_position.eph < 3.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_3_METER; - - } else if (vehicle_gps_position.eph < 10.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_10_METER; - - } else if (vehicle_gps_position.eph < 30.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_30_METER; - - } else { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_UNKNOWN; - } - - // vertical_accuracy - if (vehicle_gps_position.epv < 1.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_1_METER; - - } else if (vehicle_gps_position.epv < 3.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_3_METER; - - } else if (vehicle_gps_position.epv < 10.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_10_METER; - - } else if (vehicle_gps_position.epv < 25.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_25_METER; + msg.horizontal_accuracy = open_drone_id_translations::odidHorAccForEph(vehicle_gps_position.eph); - } else if (vehicle_gps_position.epv < 45.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_45_METER; - - } else if (vehicle_gps_position.epv < 150.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_150_METER; - - } else { - msg.vertical_accuracy = MAV_ODID_VER_ACC_UNKNOWN; - } + msg.vertical_accuracy = open_drone_id_translations::odidVerAccForEpv(vehicle_gps_position.epv); updated = true; } @@ -221,9 +170,8 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream uint64_t utc_time_msec = vehicle_gps_position.time_utc_usec / 1000; msg.timestamp = ((float)(utc_time_msec % (60 * 60 * 1000))) / 1000; - if (hrt_elapsed_time(&vehicle_gps_position.timestamp) < 1_s) { - msg.timestamp_accuracy = MAV_ODID_TIME_ACC_1_0_SECOND; // TODO - } + msg.timestamp_accuracy = open_drone_id_translations::odidTimeForElapsed(hrt_elapsed_time( + &vehicle_gps_position.timestamp)); updated = true; } @@ -236,7 +184,7 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream if (_vehicle_air_data_sub.copy(&vehicle_air_data) && (hrt_elapsed_time(&vehicle_air_data.timestamp) < 10_s)) { msg.altitude_barometric = vehicle_air_data.baro_alt_meter; - msg.barometer_accuracy = MAV_ODID_VER_ACC_150_METER; // TODO + msg.barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; // We just don't without calibration. updated = true; } } From cf19764d75250fe2f4e6df64a67738f4e011e69b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 May 2024 17:52:22 +1200 Subject: [PATCH 24/31] uavcan: implement OpenDroneID BasicID Signed-off-by: Julian Oes --- src/drivers/uavcan/CMakeLists.txt | 2 + src/drivers/uavcan/Kconfig | 4 ++ src/drivers/uavcan/remoteid.cpp | 73 ++++++++++++++++++++++++++++++ src/drivers/uavcan/remoteid.hpp | 73 ++++++++++++++++++++++++++++++ src/drivers/uavcan/rgbled.hpp | 2 +- src/drivers/uavcan/uavcan_main.cpp | 13 ++++++ src/drivers/uavcan/uavcan_main.hpp | 7 +++ 7 files changed, 173 insertions(+), 1 deletion(-) create mode 100644 src/drivers/uavcan/remoteid.cpp create mode 100644 src/drivers/uavcan/remoteid.hpp diff --git a/src/drivers/uavcan/CMakeLists.txt b/src/drivers/uavcan/CMakeLists.txt index c70d029ea7e3..f8bc1eea8a6a 100644 --- a/src/drivers/uavcan/CMakeLists.txt +++ b/src/drivers/uavcan/CMakeLists.txt @@ -147,6 +147,8 @@ px4_add_module( arming_status.hpp beep.cpp beep.hpp + remoteid.cpp + remoteid.hpp rgbled.cpp rgbled.hpp safety_state.cpp diff --git a/src/drivers/uavcan/Kconfig b/src/drivers/uavcan/Kconfig index 0076d36568f5..37306dabdfde 100644 --- a/src/drivers/uavcan/Kconfig +++ b/src/drivers/uavcan/Kconfig @@ -26,6 +26,10 @@ if DRIVERS_UAVCAN bool "Include safety state controller" default y + config UAVCAN_REMOTEID_CONTROLLER + bool "Include remote ID controller" + default y + config UAVCAN_RGB_CONTROLLER bool "Include rgb controller" default y diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp new file mode 100644 index 000000000000..7c8bc7f822cc --- /dev/null +++ b/src/drivers/uavcan/remoteid.cpp @@ -0,0 +1,73 @@ +/**************************************************************************** + * + * 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 "remoteid.hpp" +#include + +UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : + ModuleParams(nullptr), + _timer(node), + _node(node), + _uavcan_pub_remoteid_basicid(node) +{ +} + +int UavcanRemoteIDController::init() +{ + // Setup timer and call back function for periodic updates + _timer.setCallback(TimerCbBinder(this, &UavcanRemoteIDController::periodic_update)); + _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ)); + return 0; +} + +void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) +{ + if (!_vehicle_status_sub.update()) { + return; + } + + dronecan::remoteid::BasicID basic_id {}; + // basic_id.id_or_mac // supposedly only used for drone ID data from other UAs + basic_id.id_type = dronecan::remoteid::BasicID::ODID_ID_TYPE_SERIAL_NUMBER; + basic_id.ua_type = static_cast(open_drone_id_translations::odidTypeForMavType( + _vehicle_status_sub.get().system_type)); + + // uas_id: UAS (Unmanned Aircraft System) ID following the format specified by id_type + // TODO: MAV_ODID_ID_TYPE_SERIAL_NUMBER needs to be ANSI/CTA-2063 format + + char uas_id[20] = {}; + board_get_px4_guid_formated((char *)(uas_id), sizeof(uas_id)); + basic_id.uas_id = uas_id; + + _uavcan_pub_remoteid_basicid.broadcast(basic_id); +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp new file mode 100644 index 000000000000..839a2f8cf2d5 --- /dev/null +++ b/src/drivers/uavcan/remoteid.hpp @@ -0,0 +1,73 @@ +/**************************************************************************** + * + * 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 +#include + +#include +#include + +#include + +class UavcanRemoteIDController : public ModuleParams +{ +public: + UavcanRemoteIDController(uavcan::INode &node); + ~UavcanRemoteIDController() = default; + + int init(); + +private: + typedef uavcan::MethodBinder + TimerCbBinder; + + static constexpr unsigned MAX_RATE_HZ = 1; + uavcan::TimerEventForwarder _timer; + + void periodic_update(const uavcan::TimerEvent &); + + uavcan::INode &_node; + + uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; + + uavcan::Publisher _uavcan_pub_remoteid_basicid; + + //DEFINE_PARAMETERS( + // (ParamInt) _param_mode_anti_col, + // (ParamInt) _param_mode_strobe, + // (ParamInt) _param_mode_nav, + // (ParamInt) _param_mode_land + //) +}; diff --git a/src/drivers/uavcan/rgbled.hpp b/src/drivers/uavcan/rgbled.hpp index b1190214b111..be0bc876d38b 100644 --- a/src/drivers/uavcan/rgbled.hpp +++ b/src/drivers/uavcan/rgbled.hpp @@ -51,7 +51,7 @@ class UavcanRGBController : public ModuleParams int init(); private: - // Max update rate to avoid exessive bus traffic + // Max update rate to avoid excessive bus traffic static constexpr unsigned MAX_RATE_HZ = 20; void periodic_update(const uavcan::TimerEvent &); diff --git a/src/drivers/uavcan/uavcan_main.cpp b/src/drivers/uavcan/uavcan_main.cpp index fbdc534a9c30..87f3110cac7d 100644 --- a/src/drivers/uavcan/uavcan_main.cpp +++ b/src/drivers/uavcan/uavcan_main.cpp @@ -96,6 +96,9 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys #if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER) _safety_state_controller(_node), #endif +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) + _remoteid_controller(_node), +#endif #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) _rgbled_controller(_node), #endif @@ -558,6 +561,16 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events) return ret; } +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) + ret = _remoteid_controller.init(); + + if (ret < 0) { + return ret; + } + +#endif + + #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) ret = _rgbled_controller.init(); diff --git a/src/drivers/uavcan/uavcan_main.hpp b/src/drivers/uavcan/uavcan_main.hpp index 5afa04ef672e..d249e5d838cc 100644 --- a/src/drivers/uavcan/uavcan_main.hpp +++ b/src/drivers/uavcan/uavcan_main.hpp @@ -68,6 +68,10 @@ #include "logmessage.hpp" +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) +#include "remoteid.hpp" +#endif + #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) #include "rgbled.hpp" #endif @@ -269,6 +273,9 @@ class UavcanNode : public px4::ScheduledWorkItem, public ModuleParams #if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER) UavcanSafetyState _safety_state_controller; #endif +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) + UavcanRemoteIDController _remoteid_controller; +#endif #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) UavcanRGBController _rgbled_controller; #endif From de00c23e1935c9811b9d2535c220d7a9db7ed6c8 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 10 Jul 2024 13:56:19 +1200 Subject: [PATCH 25/31] uavcan: implement OpenDroneID Location --- src/drivers/uavcan/remoteid.cpp | 157 +++++++++++++++++++++++++++++++- src/drivers/uavcan/remoteid.hpp | 24 +++-- 2 files changed, 168 insertions(+), 13 deletions(-) diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 7c8bc7f822cc..987f89a97939 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -33,12 +33,17 @@ #include "remoteid.hpp" #include +#include + +using namespace time_literals; + UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : ModuleParams(nullptr), _timer(node), _node(node), - _uavcan_pub_remoteid_basicid(node) + _uavcan_pub_remoteid_basicid(node), + _uavcan_pub_remoteid_location(node) { } @@ -52,15 +57,19 @@ int UavcanRemoteIDController::init() void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) { - if (!_vehicle_status_sub.update()) { - return; - } + _vehicle_status.update(); + send_basic_id(); + send_location(); +} + +void UavcanRemoteIDController::send_basic_id() +{ dronecan::remoteid::BasicID basic_id {}; // basic_id.id_or_mac // supposedly only used for drone ID data from other UAs basic_id.id_type = dronecan::remoteid::BasicID::ODID_ID_TYPE_SERIAL_NUMBER; basic_id.ua_type = static_cast(open_drone_id_translations::odidTypeForMavType( - _vehicle_status_sub.get().system_type)); + _vehicle_status.get().system_type)); // uas_id: UAS (Unmanned Aircraft System) ID following the format specified by id_type // TODO: MAV_ODID_ID_TYPE_SERIAL_NUMBER needs to be ANSI/CTA-2063 format @@ -71,3 +80,141 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) _uavcan_pub_remoteid_basicid.broadcast(basic_id); } + +void UavcanRemoteIDController::send_location() +{ + dronecan::remoteid::Location msg {}; + + // initialize all fields to unknown + msg.status = MAV_ODID_STATUS_UNDECLARED; + msg.direction = 36100; // If unknown: 36100 centi-degrees + msg.speed_horizontal = 25500; // If unknown: 25500 cm/s + msg.speed_vertical = 6300; // If unknown: 6300 cm/s + msg.latitude = 0; // If unknown: 0 + msg.longitude = 0; // If unknown: 0 + msg.altitude_geodetic = -1000; // If unknown: -1000 m + msg.altitude_geodetic = -1000; // If unknown: -1000 m + msg.height = -1000; // If unknown: -1000 m + msg.horizontal_accuracy = MAV_ODID_HOR_ACC_UNKNOWN; + msg.vertical_accuracy = MAV_ODID_VER_ACC_UNKNOWN; + msg.barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; + msg.speed_accuracy = MAV_ODID_SPEED_ACC_UNKNOWN; + msg.timestamp = 0xFFFF; // If unknown: 0xFFFF + msg.timestamp_accuracy = MAV_ODID_TIME_ACC_UNKNOWN; + + bool updated = false; + + if (_vehicle_land_detected_sub.advertised()) { + vehicle_land_detected_s vehicle_land_detected{}; + + if (_vehicle_land_detected_sub.copy(&vehicle_land_detected) + && (hrt_elapsed_time(&vehicle_land_detected.timestamp) < 10_s)) { + if (vehicle_land_detected.landed) { + msg.status = MAV_ODID_STATUS_GROUND; + + } else { + msg.status = MAV_ODID_STATUS_AIRBORNE; + } + + updated = true; + } + } + + if (hrt_elapsed_time(&_vehicle_status.get().timestamp) < 10_s) { + if (_vehicle_status.get().failsafe && (_vehicle_status.get().arming_state == vehicle_status_s::ARMING_STATE_ARMED)) { + msg.status = MAV_ODID_STATUS_EMERGENCY; + updated = true; + } + } + + if (_vehicle_gps_position_sub.advertised()) { + sensor_gps_s vehicle_gps_position{}; + + if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) + && (hrt_elapsed_time(&vehicle_gps_position.timestamp) < 10_s)) { + + if (vehicle_gps_position.vel_ned_valid) { + const matrix::Vector3f vel_ned{vehicle_gps_position.vel_n_m_s, vehicle_gps_position.vel_e_m_s, vehicle_gps_position.vel_d_m_s}; + + // direction: calculate GPS course over ground angle + const float course = atan2f(vel_ned(1), vel_ned(0)); + const int course_deg = roundf(math::degrees(matrix::wrap_2pi(course))); + msg.direction = math::constrain(100 * course_deg, 0, 35999); // 0 - 35999 centi-degrees + + // speed_horizontal: If speed is larger than 25425 cm/s, use 25425 cm/s. + const int speed_horizontal_cm_s = matrix::Vector2f(vel_ned).length() * 100.f; + msg.speed_horizontal = math::constrain(speed_horizontal_cm_s, 0, 25425); + + // speed_vertical: Up is positive, If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. + const int speed_vertical_cm_s = roundf(-vel_ned(2) * 100.f); + msg.speed_vertical = math::constrain(speed_vertical_cm_s, -6200, 6200); + + msg.speed_accuracy = open_drone_id_translations::odidSpeedAccForVariance(vehicle_gps_position.s_variance_m_s); + + updated = true; + } + + if (vehicle_gps_position.fix_type >= 2) { + msg.latitude = static_cast(round(vehicle_gps_position.latitude_deg * 1e7)); + msg.longitude = static_cast(round(vehicle_gps_position.longitude_deg * 1e7)); + + // altitude_geodetic + if (vehicle_gps_position.fix_type >= 3) { + msg.altitude_geodetic = static_cast(round(vehicle_gps_position.altitude_msl_m)); // [m] + } + + msg.horizontal_accuracy = open_drone_id_translations::odidHorAccForEph(vehicle_gps_position.eph); + + msg.vertical_accuracy = open_drone_id_translations::odidVerAccForEpv(vehicle_gps_position.epv); + + updated = true; + } + + if (vehicle_gps_position.time_utc_usec != 0) { + // timestamp: UTC then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000 + uint64_t utc_time_msec = vehicle_gps_position.time_utc_usec / 1000; + msg.timestamp = ((float)(utc_time_msec % (60 * 60 * 1000))) / 1000; + + msg.timestamp_accuracy = open_drone_id_translations::odidTimeForElapsed(hrt_elapsed_time( + &vehicle_gps_position.timestamp)); + + updated = true; + } + } + } + + // altitude_barometric: The altitude calculated from the barometric pressue + if (_vehicle_air_data_sub.advertised()) { + vehicle_air_data_s vehicle_air_data{}; + + if (_vehicle_air_data_sub.copy(&vehicle_air_data) && (hrt_elapsed_time(&vehicle_air_data.timestamp) < 10_s)) { + msg.altitude_barometric = vehicle_air_data.baro_alt_meter; + msg.barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; // We just don't without calibration. + updated = true; + } + } + + // height: The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference + if (_home_position_sub.advertised() && _vehicle_local_position_sub.updated()) { + home_position_s home_position{}; + vehicle_local_position_s vehicle_local_position{}; + + if (_home_position_sub.copy(&home_position) + && _vehicle_local_position_sub.copy(&vehicle_local_position) + && (hrt_elapsed_time(&vehicle_local_position.timestamp) < 1_s) + ) { + + if (home_position.valid_alt && vehicle_local_position.z_valid && vehicle_local_position.z_global) { + float altitude = (-vehicle_local_position.z + vehicle_local_position.ref_alt); + + msg.height = altitude - home_position.alt; + msg.height_reference = MAV_ODID_HEIGHT_REF_OVER_TAKEOFF; + updated = true; + } + } + } + + if (updated) { + _uavcan_pub_remoteid_location.broadcast(msg); + } +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index 839a2f8cf2d5..8657ae476242 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -33,11 +33,17 @@ #pragma once +#include #include +#include +#include +#include +#include #include #include #include +#include #include @@ -58,16 +64,18 @@ class UavcanRemoteIDController : public ModuleParams void periodic_update(const uavcan::TimerEvent &); + void send_basic_id(); + void send_location(); + uavcan::INode &_node; - uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; + uORB::SubscriptionData _vehicle_status{ORB_ID(vehicle_status)}; + uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; + uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; - - //DEFINE_PARAMETERS( - // (ParamInt) _param_mode_anti_col, - // (ParamInt) _param_mode_strobe, - // (ParamInt) _param_mode_nav, - // (ParamInt) _param_mode_land - //) + uavcan::Publisher _uavcan_pub_remoteid_location; }; From d999258171d07d14cf2a42cf3b5471f0f0de4197 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 11 Jul 2024 11:06:00 +1200 Subject: [PATCH 26/31] uavcan: implement OpenDroneID System --- src/drivers/uavcan/remoteid.cpp | 38 ++++++++++++++++++++++++++++++++- src/drivers/uavcan/remoteid.hpp | 3 +++ 2 files changed, 40 insertions(+), 1 deletion(-) diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 987f89a97939..6e8bdcebeac8 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -43,7 +43,8 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : _timer(node), _node(node), _uavcan_pub_remoteid_basicid(node), - _uavcan_pub_remoteid_location(node) + _uavcan_pub_remoteid_location(node), + _uavcan_pub_remoteid_system(node) { } @@ -61,6 +62,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) send_basic_id(); send_location(); + send_system(); } void UavcanRemoteIDController::send_basic_id() @@ -218,3 +220,37 @@ void UavcanRemoteIDController::send_location() _uavcan_pub_remoteid_location.broadcast(msg); } } + +void UavcanRemoteIDController::send_system() +{ + sensor_gps_s vehicle_gps_position; + home_position_s home_position; + + if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) { + if (vehicle_gps_position.fix_type >= 3 + && home_position.valid_alt && home_position.valid_hpos) { + + dronecan::remoteid::System msg {}; + + // msg.id_or_mac // Only used for drone ID data received from other UAs. + msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF; + msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED; + msg.operator_latitude = home_position.lat * 1e7; + msg.operator_longitude = home_position.lon * 1e7; + msg.area_count = 1; + msg.area_radius = 0; + msg.area_ceiling = -1000; + msg.area_floor = -1000; + msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED; + msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED; + float wgs84_amsl_offset = vehicle_gps_position.altitude_ellipsoid_m - vehicle_gps_position.altitude_msl_m; + msg.operator_altitude_geo = home_position.alt + wgs84_amsl_offset; + + // timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. + static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019 + msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s; + + _uavcan_pub_remoteid_system.broadcast(msg); + } + } +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index 8657ae476242..3d35e5095997 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -44,6 +44,7 @@ #include #include #include +#include #include @@ -66,6 +67,7 @@ class UavcanRemoteIDController : public ModuleParams void send_basic_id(); void send_location(); + void send_system(); uavcan::INode &_node; @@ -78,4 +80,5 @@ class UavcanRemoteIDController : public ModuleParams uavcan::Publisher _uavcan_pub_remoteid_basicid; uavcan::Publisher _uavcan_pub_remoteid_location; + uavcan::Publisher _uavcan_pub_remoteid_system; }; From 04ea4f9b3a92da7c33d044cc02a046929b0f8efa Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 11 Jul 2024 14:36:54 +1200 Subject: [PATCH 27/31] uavcan: add OpenDroneID ArmStatus, operator ID In order to have operator ID be sent by QGC, we need to forward ArmStatus from the remote ID module (here on DroneCAN) to MAVLink. --- msg/CMakeLists.txt | 2 + msg/OpenDroneIdArmStatus.msg | 3 + msg/OpenDroneIdOperatorId.msg | 4 + src/drivers/uavcan/remoteid.cpp | 47 ++++++++- src/drivers/uavcan/remoteid.hpp | 18 +++- src/modules/mavlink/mavlink_main.cpp | 4 + src/modules/mavlink/mavlink_messages.cpp | 4 + src/modules/mavlink/mavlink_receiver.cpp | 21 ++++ src/modules/mavlink/mavlink_receiver.h | 5 + .../streams/OPEN_DRONE_ID_ARM_STATUS.hpp | 99 +++++++++++++++++++ 10 files changed, 205 insertions(+), 2 deletions(-) create mode 100644 msg/OpenDroneIdArmStatus.msg create mode 100644 msg/OpenDroneIdOperatorId.msg create mode 100644 src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index dce7e851dca9..0585df1ac54d 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -152,6 +152,8 @@ set(msg_files ObstacleDistance.msg OffboardControlMode.msg OnboardComputerStatus.msg + OpenDroneIdArmStatus.msg + OpenDroneIdOperatorId.msg OrbitStatus.msg OrbTest.msg OrbTestLarge.msg diff --git a/msg/OpenDroneIdArmStatus.msg b/msg/OpenDroneIdArmStatus.msg new file mode 100644 index 000000000000..1fa58c6a1f26 --- /dev/null +++ b/msg/OpenDroneIdArmStatus.msg @@ -0,0 +1,3 @@ +uint64 timestamp +uint8 status +char[50] error diff --git a/msg/OpenDroneIdOperatorId.msg b/msg/OpenDroneIdOperatorId.msg new file mode 100644 index 000000000000..0f78a47e5a8d --- /dev/null +++ b/msg/OpenDroneIdOperatorId.msg @@ -0,0 +1,4 @@ +uint64 timestamp +uint8[20] id_or_mac +uint8 operator_id_type +char[20] operator_id diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 6e8bdcebeac8..01c68aa94427 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -44,7 +44,9 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : _node(node), _uavcan_pub_remoteid_basicid(node), _uavcan_pub_remoteid_location(node), - _uavcan_pub_remoteid_system(node) + _uavcan_pub_remoteid_system(node), + _uavcan_pub_remoteid_operator_id(node), + _uavcan_sub_arm_status(node) { } @@ -53,6 +55,14 @@ int UavcanRemoteIDController::init() // Setup timer and call back function for periodic updates _timer.setCallback(TimerCbBinder(this, &UavcanRemoteIDController::periodic_update)); _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ)); + + int res = _uavcan_sub_arm_status.start(ArmStatusBinder(this, &UavcanRemoteIDController::arm_status_sub_cb)); + + if (res < 0) { + PX4_WARN("ArmStatus sub failed %i", res); + return res; + } + return 0; } @@ -63,6 +73,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) send_basic_id(); send_location(); send_system(); + send_operator_id(); } void UavcanRemoteIDController::send_basic_id() @@ -254,3 +265,37 @@ void UavcanRemoteIDController::send_system() } } } + +void UavcanRemoteIDController::send_operator_id() +{ + open_drone_id_operator_id_s operator_id; + + if (_open_drone_id_operator_id.copy(&operator_id)) { + + dronecan::remoteid::OperatorID msg {}; + + for (unsigned i = 0; i < sizeof(operator_id.id_or_mac); ++i) { + msg.id_or_mac.push_back(operator_id.id_or_mac[i]); + } + + msg.operator_id_type = operator_id.operator_id_type; + + for (unsigned i = 0; i < sizeof(operator_id.operator_id); ++i) { + msg.operator_id.push_back(operator_id.operator_id[i]); + } + + _uavcan_pub_remoteid_operator_id.broadcast(msg); + } +} + +void +UavcanRemoteIDController::arm_status_sub_cb(const uavcan::ReceivedDataStructure &msg) +{ + open_drone_id_arm_status_s arm_status{}; + + arm_status.timestamp = hrt_absolute_time(); + arm_status.status = msg.status; + memcpy(arm_status.error, msg.error.c_str(), sizeof(arm_status.error)); + + _open_drone_id_arm_status_pub.publish(arm_status); +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index 3d35e5095997..d78f365be653 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -33,18 +33,23 @@ #pragma once +#include +#include #include #include #include #include #include #include -#include +#include +#include #include #include #include #include +#include +#include #include @@ -68,6 +73,9 @@ class UavcanRemoteIDController : public ModuleParams void send_basic_id(); void send_location(); void send_system(); + void send_operator_id(); + + void arm_status_sub_cb(const uavcan::ReceivedDataStructure &msg); uavcan::INode &_node; @@ -77,8 +85,16 @@ class UavcanRemoteIDController : public ModuleParams uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _home_position_sub{ORB_ID(home_position)}; + uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)}; + uORB::Publication _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; uavcan::Publisher _uavcan_pub_remoteid_location; uavcan::Publisher _uavcan_pub_remoteid_system; + uavcan::Publisher _uavcan_pub_remoteid_operator_id; + + using ArmStatusBinder = uavcan::MethodBinder < UavcanRemoteIDController *, + void (UavcanRemoteIDController::*)(const uavcan::ReceivedDataStructure &) >; + + uavcan::Subscriber _uavcan_sub_arm_status; }; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 54e1a8549eeb..e0a4a9c2baa6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1429,6 +1429,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("OBSTACLE_DISTANCE", 1.0f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f); configure_stream_local("PING", 0.1f); configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f); @@ -1498,6 +1499,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("OPTICAL_FLOW_RAD", 10.0f); configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f); configure_stream_local("PING", 1.0f); @@ -1666,6 +1668,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("OPTICAL_FLOW_RAD", 10.0f); configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f); configure_stream_local("PING", 1.0f); @@ -1758,6 +1761,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("OPTICAL_FLOW_RAD", 1.0f); configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f); configure_stream_local("PING", 0.1f); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 638de9cce5f4..60f021a5b126 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -97,6 +97,7 @@ #include "streams/OPEN_DRONE_ID_BASIC_ID.hpp" #include "streams/OPEN_DRONE_ID_LOCATION.hpp" #include "streams/OPEN_DRONE_ID_SYSTEM.hpp" +#include "streams/OPEN_DRONE_ID_ARM_STATUS.hpp" #include "streams/OPTICAL_FLOW_RAD.hpp" #include "streams/ORBIT_EXECUTION_STATUS.hpp" #include "streams/PING.hpp" @@ -457,6 +458,9 @@ static const StreamListItem streams_list[] = { #if defined(OPEN_DRONE_ID_SYSTEM_HPP) create_stream_list_item(), #endif // OPEN_DRONE_ID_SYSTEM_HPP +#if defined(OPEN_DRONE_ID_ARM_STATUS_HPP) + create_stream_list_item(), +#endif // OPEN_DRONE_ID_ARM_STATUS_HPP #if defined(ESC_INFO_HPP) create_stream_list_item(), #endif // ESC_INFO_HPP diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 58d2c044ccd0..f54f9c158c86 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -280,6 +280,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_statustext(msg); break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: + handle_message_open_drone_id_operator_id(msg); + break; + #if !defined(CONSTRAINED_FLASH) case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: @@ -3084,6 +3088,23 @@ MavlinkReceiver::handle_message_gimbal_device_attitude_status(mavlink_message_t _gimbal_device_attitude_status_pub.publish(gimbal_attitude_status); } +void MavlinkReceiver::handle_message_open_drone_id_operator_id( + mavlink_message_t *msg) +{ + mavlink_open_drone_id_operator_id_t odid_module; + mavlink_msg_open_drone_id_operator_id_decode(msg, &odid_module); + + open_drone_id_operator_id_s odid_operator_id{}; + memset(&odid_operator_id, 0, sizeof(odid_operator_id)); + + odid_operator_id.timestamp = hrt_absolute_time(); + memcpy(odid_operator_id.id_or_mac, odid_module.id_or_mac, sizeof(odid_operator_id.id_or_mac)); + odid_operator_id.operator_id_type = odid_module.operator_id_type; + memcpy(odid_operator_id.operator_id, odid_module.operator_id, sizeof(odid_operator_id.operator_id)); + + _open_drone_id_operator_id_pub.publish(odid_operator_id); +} + void MavlinkReceiver::run() { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index b95bdca59a72..acea50284124 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -87,6 +87,7 @@ #include #include #include +#include #include #include #include @@ -182,6 +183,9 @@ class MavlinkReceiver : public ModuleParams void handle_message_obstacle_distance(mavlink_message_t *msg); void handle_message_odometry(mavlink_message_t *msg); void handle_message_onboard_computer_status(mavlink_message_t *msg); + void handle_message_open_drone_id_operator_id(mavlink_message_t *msg); + void handle_message_open_drone_id_self_id(mavlink_message_t *msg); + void handle_message_open_drone_id_system(mavlink_message_t *msg); void handle_message_optical_flow_rad(mavlink_message_t *msg); void handle_message_ping(mavlink_message_t *msg); void handle_message_play_tune(mavlink_message_t *msg); @@ -312,6 +316,7 @@ class MavlinkReceiver : public ModuleParams uORB::Publication _offboard_control_mode_pub{ORB_ID(offboard_control_mode)}; uORB::Publication _onboard_computer_status_pub{ORB_ID(onboard_computer_status)}; uORB::Publication _velocity_limits_pub{ORB_ID(velocity_limits)}; + uORB::Publication _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp new file mode 100644 index 000000000000..691ea3645533 --- /dev/null +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#ifndef OPEN_DRONE_ID_ARM_STATUS_HPP +#define OPEN_DRONE_ID_ARM_STATUS_HPP + +#include + +class MavlinkStreamOpenDroneIdArmStatus : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamOpenDroneIdArmStatus(mavlink); + } + + static constexpr const char *get_name_static() + { + return "OPEN_DRONE_ID_ARM_STATUS"; + } + static constexpr uint16_t get_id_static() + { + return MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS; + } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + return _open_drone_id_arm_status_sub.advertised() + ? MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN + + MAVLINK_NUM_NON_PAYLOAD_BYTES + : 0; + } + +private: + explicit MavlinkStreamOpenDroneIdArmStatus(Mavlink *mavlink) + : MavlinkStream(mavlink) {} + + uORB::Subscription _open_drone_id_arm_status_sub{ORB_ID(open_drone_id_arm_status)}; + + bool send() override + { + open_drone_id_arm_status_s drone_id_arm; + + if (_open_drone_id_arm_status_sub.update(&drone_id_arm)) { + + mavlink_open_drone_id_arm_status_t msg{}; + + msg.status = drone_id_arm.status; + + for (uint8_t i = 0; i < sizeof(drone_id_arm.error); ++i) { + + msg.error[i] = drone_id_arm.error[i]; + + } + + mavlink_msg_open_drone_id_arm_status_send_struct(_mavlink->get_channel(), + &msg); + + return true; + } + + return false; + } +}; + +#endif // OPEN_DRONE_ID_ARM_STATUS_HPP From 7d1d3989840fe0219e4d2ec8d8537ec4ad09fddd Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 19 Jul 2024 14:12:22 +1200 Subject: [PATCH 28/31] remoteid: add SelfID message --- msg/CMakeLists.txt | 1 + msg/OpenDroneIdSelfId.msg | 4 ++++ src/drivers/uavcan/remoteid.cpp | 24 ++++++++++++++++++++++++ src/drivers/uavcan/remoteid.hpp | 5 +++++ src/modules/mavlink/mavlink_receiver.cpp | 20 ++++++++++++++++++++ src/modules/mavlink/mavlink_receiver.h | 2 ++ 6 files changed, 56 insertions(+) create mode 100644 msg/OpenDroneIdSelfId.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 0585df1ac54d..f7465fdc002e 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -154,6 +154,7 @@ set(msg_files OnboardComputerStatus.msg OpenDroneIdArmStatus.msg OpenDroneIdOperatorId.msg + OpenDroneIdSelfId.msg OrbitStatus.msg OrbTest.msg OrbTestLarge.msg diff --git a/msg/OpenDroneIdSelfId.msg b/msg/OpenDroneIdSelfId.msg new file mode 100644 index 000000000000..1ff699ebf142 --- /dev/null +++ b/msg/OpenDroneIdSelfId.msg @@ -0,0 +1,4 @@ +uint64 timestamp +uint8[20] id_or_mac +uint8 description_type +char[23] description diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 01c68aa94427..6f66ba94cece 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -44,6 +44,7 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : _node(node), _uavcan_pub_remoteid_basicid(node), _uavcan_pub_remoteid_location(node), + _uavcan_pub_remoteid_self_id(node), _uavcan_pub_remoteid_system(node), _uavcan_pub_remoteid_operator_id(node), _uavcan_sub_arm_status(node) @@ -72,6 +73,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) send_basic_id(); send_location(); + send_self_id(); send_system(); send_operator_id(); } @@ -266,6 +268,28 @@ void UavcanRemoteIDController::send_system() } } +void UavcanRemoteIDController::send_self_id() +{ + open_drone_id_self_id_s self_id; + + if (_open_drone_id_self_id.copy(&self_id)) { + + dronecan::remoteid::SelfID msg {}; + + for (unsigned i = 0; i < sizeof(self_id.id_or_mac); ++i) { + msg.id_or_mac.push_back(self_id.id_or_mac[i]); + } + + msg.description_type = self_id.description_type; + + for (unsigned i = 0; i < sizeof(self_id.description); ++i) { + msg.description.push_back(self_id.description[i]); + } + + _uavcan_pub_remoteid_self_id.broadcast(msg); + } +} + void UavcanRemoteIDController::send_operator_id() { open_drone_id_operator_id_s operator_id; diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index d78f365be653..eb9bffd6c0e4 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -43,10 +43,12 @@ #include #include #include +#include #include #include #include +#include #include #include #include @@ -72,6 +74,7 @@ class UavcanRemoteIDController : public ModuleParams void send_basic_id(); void send_location(); + void send_self_id(); void send_system(); void send_operator_id(); @@ -86,10 +89,12 @@ class UavcanRemoteIDController : public ModuleParams uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)}; + uORB::Subscription _open_drone_id_self_id{ORB_ID(open_drone_id_self_id)}; uORB::Publication _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; uavcan::Publisher _uavcan_pub_remoteid_location; + uavcan::Publisher _uavcan_pub_remoteid_self_id; uavcan::Publisher _uavcan_pub_remoteid_system; uavcan::Publisher _uavcan_pub_remoteid_operator_id; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index f54f9c158c86..6e13f3c0ea49 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -284,6 +284,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_open_drone_id_operator_id(msg); break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: + handle_message_open_drone_id_self_id(msg); + break; + #if !defined(CONSTRAINED_FLASH) case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: @@ -3105,6 +3109,22 @@ void MavlinkReceiver::handle_message_open_drone_id_operator_id( _open_drone_id_operator_id_pub.publish(odid_operator_id); } +void MavlinkReceiver::handle_message_open_drone_id_self_id(mavlink_message_t *msg) +{ + mavlink_open_drone_id_self_id_t odid_module; + mavlink_msg_open_drone_id_self_id_decode(msg, &odid_module); + + open_drone_id_self_id_s odid_self_id{}; + memset(&odid_self_id, 0, sizeof(odid_self_id)); + + odid_self_id.timestamp = hrt_absolute_time(); + memcpy(odid_self_id.id_or_mac, odid_module.id_or_mac, sizeof(odid_self_id.id_or_mac)); + odid_self_id.description_type = odid_module.description_type; + memcpy(odid_self_id.description, odid_module.description, sizeof(odid_self_id.description)); + + _open_drone_id_self_id_pub.publish(odid_self_id); +} + void MavlinkReceiver::run() { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index acea50284124..4fa143475add 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -88,6 +88,7 @@ #include #include #include +#include #include #include #include @@ -317,6 +318,7 @@ class MavlinkReceiver : public ModuleParams uORB::Publication _onboard_computer_status_pub{ORB_ID(onboard_computer_status)}; uORB::Publication _velocity_limits_pub{ORB_ID(velocity_limits)}; uORB::Publication _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)}; + uORB::Publication _open_drone_id_self_id_pub{ORB_ID(open_drone_id_self_id)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; From cd63cfed3aaa91799e3ca94b1ecae3efd51b3013 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 19 Jul 2024 14:14:09 +1200 Subject: [PATCH 29/31] remoteid: implement System as sent from GCS This will send the System message if it is already being sent by a ground station. Otherwise, it will assemble the message itself using the takeoff/home location. --- msg/CMakeLists.txt | 1 + msg/OpenDroneIdSystem.msg | 13 ++++ src/drivers/uavcan/remoteid.cpp | 87 ++++++++++++++++-------- src/drivers/uavcan/remoteid.hpp | 2 + src/modules/mavlink/mavlink_receiver.cpp | 29 ++++++++ src/modules/mavlink/mavlink_receiver.h | 2 + 6 files changed, 106 insertions(+), 28 deletions(-) create mode 100644 msg/OpenDroneIdSystem.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index f7465fdc002e..91c38488f5aa 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -155,6 +155,7 @@ set(msg_files OpenDroneIdArmStatus.msg OpenDroneIdOperatorId.msg OpenDroneIdSelfId.msg + OpenDroneIdSystem.msg OrbitStatus.msg OrbTest.msg OrbTestLarge.msg diff --git a/msg/OpenDroneIdSystem.msg b/msg/OpenDroneIdSystem.msg new file mode 100644 index 000000000000..0604d8a42acd --- /dev/null +++ b/msg/OpenDroneIdSystem.msg @@ -0,0 +1,13 @@ +uint64 timestamp +uint8[20] id_or_mac +uint8 operator_location_type +uint8 classification_type +int32 operator_latitude +int32 operator_longitude +uint16 area_count +uint16 area_radius +float32 area_ceiling +float32 area_floor +uint8 category_eu +uint8 class_eu +float32 operator_altitude_geo diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 6f66ba94cece..1b473e8d96fc 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -236,34 +236,65 @@ void UavcanRemoteIDController::send_location() void UavcanRemoteIDController::send_system() { - sensor_gps_s vehicle_gps_position; - home_position_s home_position; - - if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) { - if (vehicle_gps_position.fix_type >= 3 - && home_position.valid_alt && home_position.valid_hpos) { - - dronecan::remoteid::System msg {}; - - // msg.id_or_mac // Only used for drone ID data received from other UAs. - msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF; - msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED; - msg.operator_latitude = home_position.lat * 1e7; - msg.operator_longitude = home_position.lon * 1e7; - msg.area_count = 1; - msg.area_radius = 0; - msg.area_ceiling = -1000; - msg.area_floor = -1000; - msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED; - msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED; - float wgs84_amsl_offset = vehicle_gps_position.altitude_ellipsoid_m - vehicle_gps_position.altitude_msl_m; - msg.operator_altitude_geo = home_position.alt + wgs84_amsl_offset; - - // timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019 - msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s; - - _uavcan_pub_remoteid_system.broadcast(msg); + open_drone_id_system_s system; + + if (_open_drone_id_system.advertised() && _open_drone_id_system.copy(&system)) { + + // Use what ground station sends us. + + dronecan::remoteid::System msg {}; + msg.timestamp = system.timestamp; + + for (unsigned i = 0; i < sizeof(system.id_or_mac); ++i) { + msg.id_or_mac.push_back(system.id_or_mac[i]); + } + + msg.operator_location_type = system.operator_location_type; + msg.classification_type = system.classification_type; + msg.operator_latitude = system.operator_latitude; + msg.operator_longitude = system.operator_longitude; + msg.area_count = system.area_count; + msg.area_radius = system.area_radius; + msg.area_ceiling = system.area_ceiling; + msg.area_floor = system.area_floor; + msg.category_eu = system.category_eu; + msg.class_eu = system.class_eu; + msg.operator_altitude_geo = system.operator_altitude_geo; + + _uavcan_pub_remoteid_system.broadcast(msg); + + } else { + // And otherwise, send our home/takeoff location. + + sensor_gps_s vehicle_gps_position; + home_position_s home_position; + + if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) { + if (vehicle_gps_position.fix_type >= 3 + && home_position.valid_alt && home_position.valid_hpos) { + + dronecan::remoteid::System msg {}; + + // msg.id_or_mac // Only used for drone ID data received from other UAs. + msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF; + msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED; + msg.operator_latitude = home_position.lat * 1e7; + msg.operator_longitude = home_position.lon * 1e7; + msg.area_count = 1; + msg.area_radius = 0; + msg.area_ceiling = -1000; + msg.area_floor = -1000; + msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED; + msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED; + float wgs84_amsl_offset = vehicle_gps_position.altitude_ellipsoid_m - vehicle_gps_position.altitude_msl_m; + msg.operator_altitude_geo = home_position.alt + wgs84_amsl_offset; + + // timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. + static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019 + msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s; + + _uavcan_pub_remoteid_system.broadcast(msg); + } } } } diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index eb9bffd6c0e4..1d1fcaa83cef 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include @@ -90,6 +91,7 @@ class UavcanRemoteIDController : public ModuleParams uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)}; uORB::Subscription _open_drone_id_self_id{ORB_ID(open_drone_id_self_id)}; + uORB::Subscription _open_drone_id_system{ORB_ID(open_drone_id_system)}; uORB::Publication _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 6e13f3c0ea49..9c53b16f3693 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -288,6 +288,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_open_drone_id_self_id(msg); break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: + handle_message_open_drone_id_system(msg); + break; + #if !defined(CONSTRAINED_FLASH) case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: @@ -3125,6 +3129,31 @@ void MavlinkReceiver::handle_message_open_drone_id_self_id(mavlink_message_t *ms _open_drone_id_self_id_pub.publish(odid_self_id); } +void MavlinkReceiver::handle_message_open_drone_id_system( + mavlink_message_t *msg) +{ + mavlink_open_drone_id_system_t odid_module; + mavlink_msg_open_drone_id_system_decode(msg, &odid_module); + + open_drone_id_system_s odid_system{}; + memset(&odid_system, 0, sizeof(odid_system)); + + odid_system.timestamp = hrt_absolute_time(); + memcpy(odid_system.id_or_mac, odid_module.id_or_mac, sizeof(odid_system.id_or_mac)); + odid_system.operator_location_type = odid_module.operator_location_type; + odid_system.classification_type = odid_module.classification_type; + odid_system.operator_latitude = odid_module.operator_latitude; + odid_system.operator_longitude = odid_module.operator_longitude; + odid_system.area_count = odid_module.area_count; + odid_system.area_radius = odid_module.area_radius; + odid_system.area_ceiling = odid_module.area_ceiling; + odid_system.area_floor = odid_module.area_floor; + odid_system.category_eu = odid_module.category_eu; + odid_system.class_eu = odid_module.class_eu; + odid_system.operator_altitude_geo = odid_module.operator_altitude_geo; + + _open_drone_id_system_pub.publish(odid_system); +} void MavlinkReceiver::run() { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 4fa143475add..39fe7c33f9c7 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -89,6 +89,7 @@ #include #include #include +#include #include #include #include @@ -319,6 +320,7 @@ class MavlinkReceiver : public ModuleParams uORB::Publication _velocity_limits_pub{ORB_ID(velocity_limits)}; uORB::Publication _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)}; uORB::Publication _open_drone_id_self_id_pub{ORB_ID(open_drone_id_self_id)}; + uORB::Publication _open_drone_id_system_pub{ORB_ID(open_drone_id_system)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; From b7c5ba17522db553a1838779b50e4b0725bc52d7 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 15 Aug 2024 08:46:15 +1200 Subject: [PATCH 30/31] boards: make flash space for remote ID over DroneCAN --- boards/ark/fmu-v6x/default.px4board | 2 -- boards/cuav/x7pro/default.px4board | 3 --- boards/px4/fmu-v4pro/test.px4board | 2 ++ boards/px4/fmu-v5/cryptotest.px4board | 2 ++ boards/px4/fmu-v5x/default.px4board | 1 - boards/px4/fmu-v6x/default.px4board | 1 - 6 files changed, 4 insertions(+), 7 deletions(-) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 92bf7cb23895..74d63e4cc33c 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -85,8 +85,6 @@ CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y -CONFIG_SYSTEMCMDS_SD_BENCH=y -CONFIG_SYSTEMCMDS_SD_STRESS=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index f72610fc65cf..4ba4d4a17754 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -79,7 +79,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DMESG=y -CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_GPIO=y CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y CONFIG_SYSTEMCMDS_I2CDETECT=y @@ -91,7 +90,6 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=y -CONFIG_SYSTEMCMDS_SD_STRESS=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y CONFIG_SYSTEMCMDS_TUNE_CONTROL=y @@ -99,4 +97,3 @@ CONFIG_SYSTEMCMDS_UORB=y CONFIG_SYSTEMCMDS_USB_CONNECTED=y CONFIG_SYSTEMCMDS_VER=y CONFIG_SYSTEMCMDS_WORK_QUEUE=y -CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/px4/fmu-v4pro/test.px4board b/boards/px4/fmu-v4pro/test.px4board index 057de060c021..51d1135a96cf 100644 --- a/boards/px4/fmu-v4pro/test.px4board +++ b/boards/px4/fmu-v4pro/test.px4board @@ -3,6 +3,8 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_GYRO_FFT=n CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_BOARD_TESTING=y diff --git a/boards/px4/fmu-v5/cryptotest.px4board b/boards/px4/fmu-v5/cryptotest.px4board index 831abbb824ab..cc31ed3c2e50 100644 --- a/boards/px4/fmu-v5/cryptotest.px4board +++ b/boards/px4/fmu-v5/cryptotest.px4board @@ -1,4 +1,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_BOARD_CRYPTO=y CONFIG_DRIVERS_STUB_KEYSTORE=y CONFIG_DRIVERS_SW_CRYPTO=y diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index a48b0956876b..8ba41726c086 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -29,7 +29,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y -CONFIG_COMMON_INS=y CONFIG_DRIVERS_IRLOCK=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 7c4bf0b6f6cb..eedfd4c90ecb 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -30,7 +30,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y -CONFIG_COMMON_INS=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y CONFIG_DRIVERS_OSD_MSP_OSD=y From 8f6ce4edbfd154a9f19c21d7927c865f5955c1ed Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 29 Aug 2024 13:40:47 +1200 Subject: [PATCH 31/31] mavlink/lib: move open_drone_id helpers to mavlink I could not extract the open_drone_id helpers to a separate lib because it would require the mavlink headers while the mavlink library would also depend on it, so it ended up being a circular dependency. Instead, I'm now just using the headers from within the mavlink module as well as from the uavcan driver. --- src/drivers/uavcan/remoteid.cpp | 2 +- src/lib/CMakeLists.txt | 1 - src/lib/open_drone_id/CMakeLists.txt | 41 ------------------- src/modules/mavlink/CMakeLists.txt | 2 +- .../mavlink}/open_drone_id_translations.cpp | 0 .../mavlink}/open_drone_id_translations.hpp | 0 .../streams/OPEN_DRONE_ID_BASIC_ID.hpp | 2 +- 7 files changed, 3 insertions(+), 45 deletions(-) delete mode 100644 src/lib/open_drone_id/CMakeLists.txt rename src/{lib/open_drone_id => modules/mavlink}/open_drone_id_translations.cpp (100%) rename src/{lib/open_drone_id => modules/mavlink}/open_drone_id_translations.hpp (100%) diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 1b473e8d96fc..a2f373b767b0 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -32,7 +32,7 @@ ****************************************************************************/ #include "remoteid.hpp" -#include +#include #include using namespace time_literals; diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 942c2dcad853..7a7b5973fd4a 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -60,7 +60,6 @@ add_subdirectory(mathlib EXCLUDE_FROM_ALL) add_subdirectory(mixer_module EXCLUDE_FROM_ALL) add_subdirectory(motion_planning EXCLUDE_FROM_ALL) add_subdirectory(npfg EXCLUDE_FROM_ALL) -add_subdirectory(open_drone_id EXCLUDE_FROM_ALL) add_subdirectory(perf EXCLUDE_FROM_ALL) add_subdirectory(fw_performance_model EXCLUDE_FROM_ALL) add_subdirectory(pid EXCLUDE_FROM_ALL) diff --git a/src/lib/open_drone_id/CMakeLists.txt b/src/lib/open_drone_id/CMakeLists.txt deleted file mode 100644 index 2090d159250e..000000000000 --- a/src/lib/open_drone_id/CMakeLists.txt +++ /dev/null @@ -1,41 +0,0 @@ -############################################################################ -# -# 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. -# -############################################################################ - -px4_add_library(open_drone_id - open_drone_id_translations.cpp - open_drone_id_translations.hpp -) - -add_dependencies(open_drone_id mavlink_c_generate) - -target_compile_options(open_drone_id PRIVATE -Wno-cast-align -Wno-address-of-packed-member) diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index 4a29a6eb0b34..45aa9b1cc82f 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -120,6 +120,7 @@ px4_add_module( mavlink_timesync.cpp mavlink_ulog.cpp MavlinkStatustextHandler.cpp + open_drone_id_translations.cpp tune_publisher.cpp MODULE_CONFIG module.yaml @@ -135,7 +136,6 @@ px4_add_module( sensor_calibration geo mavlink_c - open_drone_id timesync tunes variable_length_ringbuffer diff --git a/src/lib/open_drone_id/open_drone_id_translations.cpp b/src/modules/mavlink/open_drone_id_translations.cpp similarity index 100% rename from src/lib/open_drone_id/open_drone_id_translations.cpp rename to src/modules/mavlink/open_drone_id_translations.cpp diff --git a/src/lib/open_drone_id/open_drone_id_translations.hpp b/src/modules/mavlink/open_drone_id_translations.hpp similarity index 100% rename from src/lib/open_drone_id/open_drone_id_translations.hpp rename to src/modules/mavlink/open_drone_id_translations.hpp diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp index dcc77c660a53..b51d3e79d148 100644 --- a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp @@ -35,7 +35,7 @@ #define OPEN_DRONE_ID_BASIC_ID_HPP #include -#include +#include class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream {